Skip to content

Instantly share code, notes, and snippets.

@TheProjectsGuy
Created December 18, 2018 17:01
Show Gist options
  • Select an option

  • Save TheProjectsGuy/2123c3ae78f91534e5eb0f1e67fc5735 to your computer and use it in GitHub Desktop.

Select an option

Save TheProjectsGuy/2123c3ae78f91534e5eb0f1e67fc5735 to your computer and use it in GitHub Desktop.
Joint controllers made using C++ and Python for RViZ (ROS)
#include "ros/ros.h"
#include "math.h"
#include "ros/time.h"
#include "sensor_msgs/JointState.h"
int main(int argv, char **argc) {
// Initialize node
ros::init(argv, argc, "CPP_Joint_State_Controller");
// Node handler
ros::NodeHandle nodeHandler;
// Publisher
ros::Publisher publisherObject = nodeHandler.advertise<sensor_msgs::JointState>("joint_states", 10);
// Rate controller 5 Hz
ros::Rate rateController = ros::Rate(20);
// Variables
float angle = 0.0; // Angle
bool increment = true;
sensor_msgs::JointState msg; // Message to be published
msg.header.frame_id = ""; // Empty frame ID
msg.name.resize(1); // A 1 unit size vector
msg.position.resize(1); // A 1 unit size vector
msg.name[0] = "joint1";
// Main iterative code
while(ros::ok()) {
// Update header
msg.header.stamp = ros::Time::now(); // Assign time
msg.position[0] = angle;
publisherObject.publish(msg);
msg.header.seq ++; // Next sequence
if (increment) {
angle += 90.0/20.0 * M_PI / 180.0;
} else {
angle -= 90.0/20.0 * M_PI / 180.0;
}
if (angle > M_PI || angle < -M_PI) {
increment = !increment;
}
// Control rate
rateController.sleep();
}
// End code
return 0;
}
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import JointState
import math
def main():
# Initialize the node
rospy.init_node("Py_JointStates")
# Publisher object
publisherObject = rospy.Publisher("joint_states", JointState, queue_size=10)
# Rate controller
rateController = rospy.Rate(20)
# Variables
msg = JointState()
msg.header.frame_id = ""
msg.name = ["joint1"] # Joint name (array assignment)
angle = 0
increment = True
# Main loop
while(not rospy.is_shutdown()):
# Initialize the time of publishing
msg.header.stamp = rospy.Time.now()
# Joint angle values
msg.position = [angle]
# Publish message
publisherObject.publish(msg)
# Increase sequence
msg.header.seq += 1
# Change angle value
if increment:
angle += 90.0/20.0 * math.pi / 180.0
else:
angle -= 90.0/20.0 * math.pi / 180.0
if angle > math.pi or angle < - math.pi:
increment = not increment
# Delay execution to match rate
rateController.sleep()
if __name__ == "__main__":
try:
main()
except rospy.ROSInternalException:
rospy.logfatal("Node crashed due to an internal exception")
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment