Skip to content
Snippets Groups Projects
Commit 9857c84e authored by Don Gagne's avatar Don Gagne
Browse files

Adjust version query semantics

parent 77656b0a
No related branches found
No related tags found
No related merge requests found
...@@ -103,6 +103,9 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle ...@@ -103,6 +103,9 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
_vehicles.append(vehicle); _vehicles.append(vehicle);
// Send QGC heartbeat ASAP, this allows PX4 to start accepting commands
_sendGCSHeartbeat();
emit vehicleAdded(vehicle); emit vehicleAdded(vehicle);
setActiveVehicle(vehicle); setActiveVehicle(vehicle);
......
...@@ -198,7 +198,18 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -198,7 +198,18 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress); connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress);
// Ask the vehicle for firmware version info. This must be MAV_COMP_ID_ALL since we don't know default component id yet. // Ask the vehicle for firmware version info. This must be MAV_COMP_ID_ALL since we don't know default component id yet.
doCommandLong(MAV_COMP_ID_ALL, MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES, 1 /* request firmware version */);
mavlink_message_t versionMsg;
mavlink_command_long_t versionCmd;
versionCmd.command = MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES;
versionCmd.confirmation = 0;
versionCmd.param1 = 1; // Request firmware version
versionCmd.param2 = versionCmd.param3 = versionCmd.param4 = versionCmd.param5 = versionCmd.param6 = versionCmd.param7 = 0;
versionCmd.target_system = id();
versionCmd.target_component = MAV_COMP_ID_ALL;
mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &versionMsg, &versionCmd);
sendMessageMultiple(versionMsg);
_firmwarePlugin->initializeVehicle(this); _firmwarePlugin->initializeVehicle(this);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment