37 #include <sensor_msgs/JointState.h> 41 int main(
int argc,
char* argv[] )
43 ros::init(argc, argv,
"state_publisher" );
52 geometry_msgs::TransformStamped odom_trans;
53 sensor_msgs::JointState joint_state;
60 joint_state.name.resize(6);
61 joint_state.position.resize(6);
63 joint_state.name[0] =
"base_top_joint";
64 joint_state.position[0] = 0;
66 joint_state.name[1] =
"base_swivel_joint";
67 joint_state.position[1] = 0;
69 joint_state.name[2] =
"swivel_hubcap_joint";
70 joint_state.position[2] = 0;
72 joint_state.name[3] =
"center_wheel_joint";
73 joint_state.position[3] = 0;
75 joint_state.name[4] =
"base_front_joint";
76 joint_state.position[4] = 0;
78 joint_state.name[5] =
"base_back_joint";
79 joint_state.position[5] = 0;
83 joint_state_publisher.
publish(joint_state);
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)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char *argv[])