32 #include <geometry_msgs/TransformStamped.h> 33 #include <sensor_msgs/JointState.h> 39 #include <sys/types.h> 51 std::map<std::string, ros::Subscriber>
subs_;
55 void cbJoint(
const sensor_msgs::JointState::ConstPtr& msg)
57 for (
size_t i = 0; i < msg->name.size(); i++)
59 geometry_msgs::TransformStamped trans;
60 trans.header = msg->header;
61 trans.header.frame_id = msg->name[i] +
"_in";
62 trans.child_frame_id = msg->name[i] +
"_out";
81 int main(
int argc,
char* argv[])
83 ros::init(argc, argv,
"joint_tf_publisher");
int main(int argc, char *argv[])
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::map< std::string, ros::Subscriber > subs_
ROSCPP_DECL void spin(Spinner &spinner)
tf2_ros::TransformBroadcaster tf_broadcaster_
void cbJoint(const sensor_msgs::JointState::ConstPtr &msg)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints())
const tf2::Vector3 z_axis_