The kinematics controller for the articulated vehicle consists of two separate components: a powered unit called the tractor or truck, and a trailer or semi-trailer that is attached to the tractor using a pivoting joint.
The base_link is set to the axis of the tractor's wheels, therefore the angular velocity for the tractor is defined as:
Where
Parameters
With the simplified non-slipping model, the velocity of vehicle's orientation is:
Where
Therefore the steering angle command can be deduced as:
Due to the tractor-trailer structure, the forms of the footprint change while the vehicle is turning. The fixed forms of the footprint will mislead the interference of occlusion. Fortunately, the costmap_2d subscribes to the footprint topic with geometry_msgs/Polygon message type, which provides a way for users to publish dynamically changing forms of the footprint
whi_articulated_steering_controller publishes the footprint with user configured topic:
In the controller's parameter yaml file, set the following ones with specified values:
# Dynamic footprint
topic: footprint
trailer_top_left: [0.25, 0.08]
trailer_top_right: [0.25, -0.08]
tractor_bottom_left: [-0.08, 0.08]
tractor_bottom_right: [-0.08, -0.08]
In costmap's parameter yaml file, add the parameter "footprint_topic" if there is none, and set its value aligned with the one in the controller's parameter file:
footprint_topic: /whi_01/NaviBOT/controller/base_controller/footprint
NOTE: set the footprint_topic with an absolute path, which should include the full namespace, like the above example
-
odom (nav_msgs/Odometry)
Odometry is computed from the hardware feedback.
-
/tf (tf/tfMessage).
Transform from odom to base_footprint.
-
cmd_vel_out (geometry_msgs/TwistStamped).
Available when "publish_cmd" parameter is set to True. It is the Twist after limiters have been applied to the controller input.