How to publish float64 array to a topic?
Hello, I am trying to publish fake joint states on a topic. My code compiles successfully, however, it gives an error "Segmentation fault, core dumped" when is run the node. Basically, I want to publish two fake positions (0) and two velocities.
#include<ros/ros.h>
#include<std_msgs/Float64.h>
#include <sensor_msgs/JointState.h>
float lVel = 0, rVel = 0, lPos = 0, rPos = 0;
int main(int argc, char** argv){
ros::init(argc, argv, "custom_joint_state_publisher");
ros::NodeHandle n;
ros::Publisher statePub = n.advertise<sensor_msgs::JointState>("measured_joint_states", 100);
sensor_msgs::JointState joint_values;
ros::Rate r(10);
while(ros::ok()){
joint_values.header.stamp = ros::Time::now();
joint_values.position[0] = 0 ;
joint_values.position[1] = 0;
joint_values.velocity.push_back(0);
joint_values.velocity.push_back(0);
statePub.publish(joint_values);
r.sleep();
ros::spinOnce();
}
return 0;
}
Here you can see that I am using the assignment operator and pushback() function. The segmentation fault error appears with the assignment operator only. The issue with push_back function is that instead of publishing one value (0), it publishes multiple values (array of 0s) on the topic. How to publish one 0 at a time to the topic? I am using ROS melodic, Ubuntu 18.04. Thank you!
Similar questions:
https://answers.ros.org/question/3808...
https://answers.ros.org/question/2734...
https://answers.ros.org/question/3933...
https://answers.ros.org/question/3721...
Thank you for comment. I actually went through above links but couldn't fix the issue i am facing.
Please edit your question so your code is easy readable, only then we could help
Just to note: the OP is not publishing "a
float64
topic". This is a regularJointState
publisher.Sorry, i didn't know how to do that but someone did that for me. Thanks to him.