Skip to content

Commit

Permalink
Blimp: handle MAV_CMD_NAV_TAKEOFF via command_long and command_in
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Oct 18, 2023
1 parent 0caceb1 commit b79fb43
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 4 deletions.
15 changes: 11 additions & 4 deletions Blimp/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -475,6 +475,8 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_in
switch (packet.command) {
case MAV_CMD_DO_REPOSITION:
return handle_command_int_do_reposition(packet);
case MAV_CMD_NAV_TAKEOFF:
return MAV_RESULT_ACCEPTED;
default:
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
}
Expand All @@ -484,10 +486,6 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_l
{
switch (packet.command) {

case MAV_CMD_NAV_TAKEOFF: {
return MAV_RESULT_ACCEPTED;
}

case MAV_CMD_CONDITION_YAW:
// param1 : target angle [0-360]
// param2 : speed during change [deg per second]
Expand All @@ -510,6 +508,15 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_l
}
}

bool GCS_MAVLINK_Blimp::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const
{
if (packet_command == MAV_CMD_NAV_TAKEOFF) {
frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
return true;
}
return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command);
}

void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg)
{
switch (msg.msgid) {
Expand Down
1 change: 1 addition & 0 deletions Blimp/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ class GCS_MAVLINK_Blimp : public GCS_MAVLINK
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);

bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;

bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
Expand Down

0 comments on commit b79fb43

Please sign in to comment.