ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
You can do everything inside your odomCallback
function
void OdomToTransform::odomCallback(const nav_msgs::OdometryConstPtr& msg) {
geometry_msgs::TransformStamped tf_stamped;
tf_stamped.header = msg.header;
tf_stamped.child_frame_id = msg.child_frame_id;
tf_stamped.transform.translation.x = msg.pose.pose.position.x;
tf_stamped.transform.translation.y = msg.pose.pose.position.y;
tf_stamped.transform.translation.z = msg.pose.pose.position.z;
tf_stamped.transform.rotation = msg.pose.pose.orientation;
transform_pub_.publish(tf_stamped);
}
2 | No.2 Revision |
You can do everything inside your odomCallback
function
void OdomToTransform::odomCallback(const nav_msgs::OdometryConstPtr& msg) nav_msgs::Odometr &msg) {
geometry_msgs::TransformStamped tf_stamped;
tf_stamped.header = msg.header;
tf_stamped.child_frame_id = msg.child_frame_id;
tf_stamped.transform.translation.x = msg.pose.pose.position.x;
tf_stamped.transform.translation.y = msg.pose.pose.position.y;
tf_stamped.transform.translation.z = msg.pose.pose.position.z;
tf_stamped.transform.rotation = msg.pose.pose.orientation;
transform_pub_.publish(tf_stamped);
}
3 | No.3 Revision |
You can do everything inside your odomCallback
function
void OdomToTransform::odomCallback(const nav_msgs::Odometr nav_msgs::Odometry &msg) {
geometry_msgs::TransformStamped tf_stamped;
tf_stamped.header = msg.header;
tf_stamped.child_frame_id = msg.child_frame_id;
tf_stamped.transform.translation.x = msg.pose.pose.position.x;
tf_stamped.transform.translation.y = msg.pose.pose.position.y;
tf_stamped.transform.translation.z = msg.pose.pose.position.z;
tf_stamped.transform.rotation = msg.pose.pose.orientation;
transform_pub_.publish(tf_stamped);
}
4 | No.4 Revision |
You can do everything inside your odomCallback
function
void OdomToTransform::odomCallback(const nav_msgs::Odometry &msg) {
odometry_ = msg;
geometry_msgs::TransformStamped tf_stamped;
tf_stamped.header = msg.header;
odometry_.header;
tf_stamped.child_frame_id = msg.child_frame_id;
odometry_.child_frame_id;
tf_stamped.transform.translation.x = msg.pose.pose.position.x;
odometry_.pose.pose.position.x;
tf_stamped.transform.translation.y = msg.pose.pose.position.y;
odometry_.pose.pose.position.y;
tf_stamped.transform.translation.z = msg.pose.pose.position.z;
odometry_.pose.pose.position.z;
tf_stamped.transform.rotation = msg.pose.pose.orientation;
odometry_.pose.pose.orientation;
transform_pub_.publish(tf_stamped);
}