Gimbal
This module wraps the SDK class rm:robomaster.gimbal.Gimbal
to get the state and control the gimbal.
If the module is enabled, the ROS driver when initializing will recenter the gimbal and set the coupling control model between gimbal and chassis to mode.
State Estimation
Information from rm:robomaster.gimbal.Gimbal.sub_angle()
is republished
to joint_states_p (joints gimbal_joint
and blaster_joint
of model gimbal.urdf.xacro)
at the rate configured by parameter gimbal.rate.
Control
The gimbal can be controlled in velocity, publishing target angular speeds on cmd_gimbal, or by giving a goal orientation (in specific coordinate frames) to action move_gimbal, together with maximal rotation speeds. Action recenter_gimbal recenter the gimbal.
To stop the gimbal, either send a zero velocity target or a zero relative target orientation, To engage or disengage the gimbel motors, use gimbal/engage.
Yaw control coupling mode between gimbal and chassis
The robot onboard controller can be configured to couple the controllers of gimbal and chassis yaws, in one of three modes:
- chassis is leading
The gimbal will keep the same relative orientation with the chassis, effectively locking yaw rotations.
- gimbal is leading
The chassis will actively rotate to keep the same relative orientation.
- free
The two controllers are decoupled. When the chassis rotates, the gimbal (if no other commands are provided) will maintain absolute orientation, until it reaches the limits of yaw rotations.
The initial coupling mode is configured by the value of parameter :mode. To change mode, send a command to mode.
Warning
Gimbal control commands will change the coupling mode: velocity commands on cmd_gimbal will stop making the gimbal follows the chassis.
Command gimbal/lock lock the gimbal to the chassis, freezing both yaw and pitch rotations.
Parameters
-
parameter gimbal.enabled bool [Default:
false
] Enables all the ROS interface described here, which by default is disabled, like all other modules.
-
parameter mode int [Default:
2
] A value between 0 and 2, see the enum in robomaster_msgs/msg/Mode: 0 free, 1 gimbal leads, 2 chassis leads.
-
parameter gimbal.rate int [Default:
10
] The rate in Hz at which joint_states_p (with gimbal joints) is published. One of
0, 1, 5, 10, 20, 50
(else it will approximate to the nearest value). A value of0
will effectively disable updates.
Subscription
- subscription cmd_gimbal robomaster_msgs/msg/GimbalCommand
Listen for velocity commands to control yaw and pitch speed of the gimbal using
rm:robomaster.gimbal.Gimbal.drive_speed()
.
- subscription mode robomaster_msgs/msg/Mode
Listen to commands to change the yaw coupling mode between gimbal and chassis.
- subscription gimbal/lock std_msgs/msg/Bool
Listen for commands to lock the gimbal to the frame (when
msg.data
is true).
- subscription gimbal/engage std_msgs/msg/Bool
Listen for commands to engage or disengage the gimbal motors.
Action Servers
- action server move_gimbal robomaster_msgs/action/MoveGimbal
Pass a target orientation in one of the 4 coordinate frame described in robomaster_msgs/action/MoveGimbal to an onboard action, which terminates when the gimbal reaches the goal.
- action server recenter_gimbal robomaster_msgs/action/RecenterGimbal
Recenter the gimbal using onboard control triggered by a different SDK action
rm:robomaster.gimbal.Gimbal.recenter()
. The action terminates when the gimbal reaches zero yaw and pitch with respect to the chassis.
Warning
The two action are mutually exclusive: the ROS driver avoid triggering both in parallel. Moreover, new action goals are not accepted if a current goal is active. Therefore, to call a different action or to change goal, you first need to cancel the current goal.