Switching modes in PX4 using ROS2 and uxrce_dds

I’m running a px4 sitl and using ros2, subscribing to the vehicle status, once in misson mode, I’m trying to switch to hold or loiter mode. To switch commands I’m using vehicle command topic. What is the param values for loiter and hold mode. I’m unable to find any ref.

import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy, DurabilityPolicy
from px4_msgs.msg import VehicleCommand, VehicleStatus, VehicleLocalPosition

class Switch(Node):

    def __init__(self):
        super().__init__('switch_mode')

    #Quality of service
        qos_profile = QoSProfile(
            reliability=ReliabilityPolicy.BEST_EFFORT,
            durability=DurabilityPolicy.TRANSIENT_LOCAL,
            history=HistoryPolicy.KEEP_LAST,
            depth=1
        )

        # publishers
        self.vehicle_command_publisher = self.create_publisher(
            VehicleCommand,
            '/fmu/in/vehicle_command',
            10)

        # subscribers
        self.vehicle_status_subscriber = self.create_subscription(
            VehicleStatus,
            '/fmu/out/vehicle_status',
            self.vehicle_status_callback,
            qos_profile)
        
        self.vehicle_local_position_subscriber = self.create_subscription(
            VehicleLocalPosition,
            '/fmu/out/vehicle_local_position',
            self.vehicle_local_position_callback,
            qos_profile)
     
        self.in_mission_mode = False
        self.takeoff_height = -4.0  # Adjust the takeoff height as needed

    # vehicle local position callback
    def vehicle_local_position_callback(self, msg):
        self.vehicle_local_position = msg

    # drone status callback
    def vehicle_status_callback(self, msg):
        self.get_logger().info(f"Vehicle status callback: {msg.nav_state}")
        if msg.nav_state == VehicleStatus.NAVIGATION_STATE_AUTO_MISSION and self.vehicle_local_position.z < self.takeoff_height:
            self.in_mission_mode = True
            self.publish_vehicle_command(VehicleCommand.VEHICLE_CMD_DO_SET_MODE, param1 = 1.0)
            self.get_logger().info('Vehicle command published') 


    #publishes command to drone
    def publish_vehicle_command(self, command, **params):
        """Publish a vehicle command."""
        msg = VehicleCommand()
        msg.command = command
        msg.param1 = params.get("param1", 0.0)
        msg.param2 = params.get("param2", 0.0)
        msg.param3 = params.get("param3", 0.0)
        msg.param4 = params.get("param4", 0.0)
        msg.param5 = params.get("param5", 0.0)
        msg.param6 = params.get("param6", 0.0)
        msg.param7 = params.get("param7", 0.0)
        msg.target_system = 1
        msg.target_component = 1
        msg.source_system = 1
        msg.source_component = 1
        msg.from_external = True
        msg.timestamp = int(self.get_clock().now().nanoseconds / 1000)
        self.vehicle_command_publisher.publish(msg)

def main(args=None):
    
    rclpy.init(args=args)
    node = Switch()
    rclpy.spin(node)
    rclpy.shutdown()

if __name__=='__main__':
    main()

@Benja @Jaeyoung-Lim

Hi @Neo_man
The parameter values for the different modes are defined here and you can see here how the command are actually assembled in the commander module when you type commander mode *** in the shell.

These are the lines for loiter mode:

} else if (!strcmp(argv[1], "auto:loiter")) {
  send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_AUTO,
    PX4_CUSTOM_SUB_MODE_AUTO_LOITER);

Hi @Benja , Thanks for the prompt reply. I have already gone through this from your previous conversation here .But I would like to actually know how the params are set, for example to switch to offboard mode the params are as given below.

self.publish_vehicle_command(VehicleCommand.VEHICLE_CMD_DO_SET_MODE, param1 = 1.0, param2 = 6.0)

    def publish_vehicle_command(self, command, **params):
        """Publish a vehicle command."""
        msg = VehicleCommand()
        msg.command = command
        msg.param1 = params.get("param1", 0.0)
        msg.param2 = params.get("param2", 0.0)
        msg.param3 = params.get("param3", 0.0)
        msg.param4 = params.get("param4", 0.0)
        msg.param5 = params.get("param5", 0.0)
        msg.param6 = params.get("param6", 0.0)
        msg.param7 = params.get("param7", 0.0)
        msg.target_system = 1
        msg.target_component = 1
        msg.source_system = 1
        msg.source_component = 1
        msg.from_external = True
        msg.timestamp = int(self.get_clock().now().nanoseconds / 1000)
        self.vehicle_command_publisher.publish(msg)

So, how do I identify params for other cases(like hold, loiter)?

TLDR

for loiter

self.publish_vehicle_command(VehicleCommand.VEHICLE_CMD_DO_SET_MODE, param1 = 1.0, param2 = 4.0, param3 =3.0)

you need param3

Long explanation

Here is where the commander module parse the VEHICLE_CMD_DO_SET_MODE

param1 is base_mode
param2 is custom_main_mode
param3 is custom_sub_mode

This is the switching logic for loiter (all the others are in the same page)

The values for PX4_CUSTOM_MAIN_MODE_AUTO and PX4_CUSTOM_SUB_MODE_AUTO_LOITER are defined here

1 Like

@Benja. Thanks for taking time and providing a long explanation, this is very helpful. Really appreciate the effort.

@Neo_man Happy to help!
Please mark my answer as solution for future reference :slight_smile: