ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Couple of notes:
base_footprint
and camera_rgb_optical_frame
would not be provided by a static transform publisher, but would instead be provided by the URDF and an instance of the robot_state_publisher
. Based on the tf
tree linked in the question, that would mean that the camera_link
would need to be added to the URDF.static_transform_publisher
. In your case, I see a few problems with the first <node>
tag in your launch file:
odom
frame represents how the robot thinks it has moved while driving around (i.e. the transform from odom
to base_footprint
comes from odometry information such as wheel encoders and IMUs). If your camera is attached to your robot, the transform from odom
to camera_link
would not be static, it would be a function of odometry (meaning a static transform publisher would not be appropriate). I doubt you actually mean to express the pose of the camera w.r.t. the odom
frame. Rather, the you likely want to express the camera_link
w.r.t. the base_link
(you'd be specifying the pose of the camera relative to the base_link
of your robot, which never changes).static_transform_publisher
are invalid. If you study the docs for the arguments that the static_transform_publisher
accepts you'll see that there are 2 forms: the first uses 6 floats before the frame_id
and represents rotation as RPY, and the second uses 7 floats before frame_id
and represents rotation as a Quaternion. You are using 7, but the provided Quaternion is invalid because its norm is not 1.0 (you have all zeros). An identity quaternion would be 0 0 0 1
. This mistake is where the TF_NAN_INPUT
is likely coming from in your second error message.2 | No.2 Revision |
Couple of notes:
base_footprint
and camera_rgb_optical_frame
would not be provided by a static transform publisher, but would instead be provided by the URDF and an instance of the robot_state_publisher
. Based on the tf
tree linked in the question, that would mean that the camera_link
would need to be added to the URDF.static_transform_publisher
. In your case, I see a few problems with the first <node>
tag in your launch file:
odom
frame represents how the robot thinks it has moved while driving around (i.e. the transform from odom
to base_footprint
comes from odometry information such as wheel encoders and IMUs). If your camera is attached to your robot, the transform from odom
to camera_link
would not be static, it would be a function of odometry (meaning a static transform publisher would not be appropriate). I doubt you actually mean to express the pose of the camera w.r.t. the odom
frame. Rather, the you likely want to express the camera_link
w.r.t. the base_link
(you'd be specifying the pose of the camera relative to the base_link
of your robot, which never changes).static_transform_publisher
are invalid. If you study the docs for the arguments that the static_transform_publisher
accepts you'll see that there are 2 forms: the first uses 6 floats before the frame_id
and represents rotation as RPY, and the second uses 7 floats before frame_id
and represents rotation as a Quaternion. You are using 7, but the provided Quaternion is invalid because its norm is not 1.0 (you have all zeros). An identity quaternion would be 0 0 0 1
. This mistake is where the TF_NAN_INPUT
is likely coming from in your second error message.3 | No.3 Revision |
Couple of notes:
base_footprint
and camera_rgb_optical_frame
would not be provided by a static transform publisher, but would instead be provided by the URDF and an instance of the robot_state_publisher
. Based on the tf
tree linked in the question, that would mean that the camera_link
would need to be added to the URDF.static_transform_publisher
. In your case, I see a few problems with the first <node>
tag in your launch odom
frame represents how the robot thinks it has moved while driving around (i.e. the transform from odom
to base_footprint
comes from odometry information such as wheel encoders and IMUs). If your camera is attached to your robot, the transform from odom
to camera_link
would not be static, it would be a function of odometry (meaning a static transform publisher would not be appropriate). I doubt you actually mean to express the pose of the camera w.r.t. the odom
frame. Rather, the you likely want to express the camera_link
w.r.t. the base_link
(you'd be specifying the pose of the camera relative to the base_link
of your robot, which never changes).static_transform_publisher
are invalid. If you study the docs for the arguments that the static_transform_publisher
accepts you'll see that there are 2 forms: the first uses 6 floats before the frame_id
and represents rotation as RPY, and the second uses 7 floats before frame_id
and represents rotation as a Quaternion. You are using 7, but the provided Quaternion is invalid because its norm is not 1.0 (you have all zeros). An identity quaternion would be 0 0 0 1
. This mistake is where the TF_NAN_INPUT
is likely coming from in your second error message.