COMMAND_ACK:UNSUPPORTED when using COMMAND_INT

Sending MAVLink messages via Command_Int is returning COMMAND_ACK:[COMMAND_NAME]:UNSUPPORTED. I am using MAVROS built using ROS2 Foxy to pack and send these commands, using the Command_Long MAVROS service to send a Set_Mode message works but returns COMMAND_ACK:DO_SET_MODE:DENIED when trying to use COMMAND_INT. I have sent the message with frames, MAV_FRAME_GLOBAL, MAV_FRAME_LOCAL_NED, MAV_FRAME_MISSION, MAV_FRAME_GLOBAL_RELATIVE_ALT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT to no avail.

Current usage:

auto request = std::make_shared<mavros_msgs::srv::CommandInt::Request>();
                request->frame = mavros_msgs::msg::Waypoint::FRAME_GLOBAL_REL_ALT;
                request->command = 113;
                request->current = 0;
                request->autocontinue = 0;
                request->param1 = 0;                        
                request->param2 = 0;                        
                request->param3 = 0;                        
                request->param4 = 0;                        
                request->x = 0;                        
                request->y = 0;                       
                request->z = alt; (altitude in meters)
                                                                      
                auto result = comm_client_->async_send_request(request);

Hello @nraines , welcome to the community,

In version 4.4.4 some mavlink commands are only accepted as COMMAND_INT, some only as COMMAND_LONG, some not at all, and some in both COMMAND and COMMAND_LONG.

So find a combination that works for you.

Commands get denied when certain conditions are not met, like for example no GPS signal.

Starting with ArduCopter 4.5.0 all commands are accepted in both COMMAND_INT and COMMAND_LONG. But COMMAND_INT is preferred.

COMMAND_LONG support is scheduled for deprecation: https://github.com/ArduPilot/ardupilot/blob/master/libraries/GCS_MAVLink/GCS_config.h#L95

Hey Amilcar,

I just tried this with version 4.5.0. Sending the MAV_CMD_CONDITION_CHANGE_ALT command with the COMMAND_INT message still gives me the respone from the autopilot: “Got COMMAND_ACK:CONDITION_CHANGE_ALT:UNSUPPORTED”.

ISSUE RESOLVED:

To anyone having this issue, only specific commands are accepted when sent using COMMAND_INT, see wiki: https://ardupilot.org/dev/docs/copter-commands-in-guided-mode.html