6 #include <sensor_msgs/JointState.h> 8 int main(
int argc,
char** argv) {
9 ros::init(argc, argv,
"robot_joint_state_publisher");
12 std::vector<std::string> joint_names;
13 node_handle.
getParam(
"joint_names", joint_names);
16 node_handle.
getParam(
"robot_ip", robot_ip);
19 node_handle.
getParam(
"publish_rate", publish_rate);
23 sensor_msgs::JointState states;
24 states.effort.resize(joint_names.size());
25 states.name.resize(joint_names.size());
26 states.position.resize(joint_names.size());
27 states.velocity.resize(joint_names.size());
29 for (
size_t i = 0; i < joint_names.size(); i++) {
30 states.name[i] = joint_names[i];
40 for (
size_t i = 0; i < joint_names.size(); i++) {
41 states.position[i] = robot_state.
q[i];
42 states.velocity[i] = robot_state.
dq[i];
43 states.effort[i] = robot_state.
tau_J[i];
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::array< double, 7 > q
int main(int argc, char **argv)
std::array< double, 7 > dq
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void read(std::function< bool(const RobotState &)> read_callback)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
std::array< double, 7 > tau_J