Commit 4c26d4ae authored by Léo-Paul Géneau's avatar Léo-Paul Géneau 👾

Use DO_PARACHUTE command to pop parachute

parent d8fb73fc
......@@ -173,7 +173,7 @@ int updateLogAndProjection(void) {
<< position.latitude_deg << ";" << position.longitude_deg << ";"
<< position.absolute_altitude_m << ";" << position.relative_altitude_m << ";"
<< telemetry->attitude_euler().yaw_deg << ";"
<< metrics.velocity_m_s << ";" << metrics.climb_rate_m_s;
<< metrics.airspeed_m_s << ";" << metrics.climb_rate_m_s;
log(oss.str());
if (projected_destination.latitude != 0 || targeted_destination.latitude != 0) {
......@@ -294,8 +294,8 @@ int triggerParachute(void) {
log("Landing...");
MavlinkPassthrough::CommandLong command;
command.command = MAV_CMD_DO_FLIGHTTERMINATION;
command.param1 = 1; //see https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FLIGHTTERMINATION
command.command = MAV_CMD_DO_PARACHUTE;
command.param1 = 2; //see https://mavlink.io/en/messages/common.html#PARACHUTE_ACTION
command.target_sysid = mavlink_passthrough->get_target_sysid();
command.target_compid = mavlink_passthrough->get_target_compid();
return doMavlinkCommand(command, "Parachute release failed");
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment