The PointCloud2 topic appearing above the robot in rviz is due to differences in the frame definitions between gazebo/ros and OpenCV.
The solution to this problem is to create a camera_link_optical
in the urdf
using rpy
values:
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}" />
Then you have to set the gazebo reference frame within the <sensor><plugin/></sensor>
tags.
Online answers will show that using the tag frameName
will accomplish this. THIS WILL NOT WORK as ROS2 has changed the syntax of this tag. In order to set the Gazebo frame reference, use the
<frame_name>camera_link_optical</frame_name>
This will rotate the PointCloud2 orientation to be in the correct location relative to the robot.
type
not setA common error when trying to load joint controllers will say that the controller type
or command_interface
is not set. This can be due to controller.yaml
typos or errors, or can be another common issue. One way to check is by using the ros2 control list_hardware_interfaces
command.
ros2 control list_hardware_interfaces
command interfaces
wheel_joint1/position [available] [claimed]
wheel_joint1/velocity [available][claimed]
wheel_joint2/position [unavailable] [unclaimed]
wheel_joint2/velocity [unavailable] [unclaimed]
This is the common output as a result of this error. You will have tried to initialize multiple joints, but only 1 joint will be in blue. The other joints will show that they are [unavailable]
and [unclaimed]
.
The cause of this error is due to XACRO
definitions that call on the <ros2_control>
tag more than once.
When creating your xacro
macros, Leave the ros2_control
tag in the main xacro
document, then call on your xacro:macro
function inside those tags
<ros2_control>
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<xacro:wheel_control
name="front"
steer_limlow="${-35 * deg_to_rad}"
steer_limhigh="${35 * deg_to_rad}"/>
</ros2_control>
Place all macros
within tags, then controllers will be properly loaded.
A common error when building ROS2 packages will include the error note: