Control Gimbal over MicroRTPS & ROS2

I am currently trying to control gimbal over ROS2 through AUX on firmware 1.13.3

PX4 Firmware

Build firmware with micrortps & add uorb topics

### urtps_bridge_topics.yaml
...
  - msg:     mount_orientation 
    send:    true
    receive: true
    id:      27
  - msg:     gimbal_device_attitude_status 
    send:    true
    id:      28
  - msg:     gimbal_device_information 
    send:    true
    id:      29
  - msg:     gimbal_device_set_attitude 
    receive: true
    id:      30
  - msg:     gimbal_manager_information 
    send:    true
    id:      31
  - msg:     gimbal_manager_set_attitude 
    receive: true
    id:      32
  - msg:     gimbal_manager_set_manual_control 
    receive: true
    id:      33
  - msg:     gimbal_manager_status 
    send:    true
    id:      34

Got it micrortps_agent & micrortps_cilent running correctly.

PX4 6X param:

SYS_CTRL_ALLOC = 1
MNT_MODE_IN = Mavlink gimbal protocal v2
MNT_MODE_OUT = AUX
COM_PREARM_MODE=2 (For testing)

Set AUX 1-3 to Gimbal Roll, Yaw & Pitch.

Mavlink Console:
Got gimbal moving over console

gimbal status # ensure it is running
gimbal test pitch 45 yaw 45

Able to get status from /fmu/gimbal_device_set_attitude/in

timestamp: 1704841450199713
target_system: 0
target_component: 0
device_flags: 30
q:
- 1.0
- 0.0
- 0.0
- 0.0
angular_velocity_x: 0.0
angular_velocity_y: 0.0
angular_velocity_z: 0.0
failure_flags: 0
received_from_mavlink: false

However unable to control the gimbal over ROS2 & uorb when publishing over /fmu/gimbal_manager_set_manual_control/in

Is there anyone got it running? Im looking at trying it with gimbal V1 command. Is there a set got it working controlling gimbal through AUX over microRTPS.

1 Like

Rechecking, might try controlling over actuator_control.

Got it working

    px4_msgs::msg::VehicleCommand vehicle_command_{};

    vehicle_command_.command = vehicle_command_.VEHICLE_CMD_DO_MOUNT_CONTROL;
    vehicle_command_.param1 = 0.0f; // Gimbal pitch
    vehicle_command_.param2 = 0;    // Gimbal roll (not used)
    vehicle_command_.param3 = 0.0f; // Gimbal yaw
    vehicle_command_.param4 = 0;
    vehicle_command_.param5 = 0;
    vehicle_command_.param6 = 0;
    vehicle_command_.param7 = vehicle_command_.VEHICLE_MOUNT_MODE_MAVLINK_TARGETING;
    // vehicle_command_.target_system = 1;
    // vehicle_command_.target_component = 1;
    // vehicle_command_.source_system = 1;
    // vehicle_command_.source_component = 1;
    // vehicle_command_.from_external = true;
    vehicle_command_.timestamp = this->get_clock()->now().nanoseconds() / 1000;

    vehicle_command_publisher_->publish(vehicle_command_);

    RCLCPP_INFO(this->get_logger(), "
1 Like