Skip to content

Commit

Permalink
Merge pull request #1487 from mavlink/pr-fix-mavlink-mission-sysid-co…
Browse files Browse the repository at this point in the history
…mpid

core: fix own sysid/compid in mission transfer
  • Loading branch information
julianoes committed Jul 22, 2021
2 parents 6f9358e + 75480de commit 5a9289e
Show file tree
Hide file tree
Showing 6 changed files with 115 additions and 401 deletions.
80 changes: 40 additions & 40 deletions src/core/mavlink_mission_transfer.cpp
Expand Up @@ -211,11 +211,11 @@ void MAVLinkMissionTransfer::UploadWorkItem::send_count()
{
mavlink_message_t message;
mavlink_msg_mission_count_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
_items.size(),
_type);

Expand All @@ -232,11 +232,11 @@ void MAVLinkMissionTransfer::UploadWorkItem::send_cancel_and_finish()
{
mavlink_message_t message;
mavlink_msg_mission_ack_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
MAV_MISSION_OPERATION_CANCELLED,
_type);

Expand Down Expand Up @@ -279,11 +279,11 @@ void MAVLinkMissionTransfer::UploadWorkItem::process_mission_request(

mavlink_message_t message;
mavlink_msg_mission_ack_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
MAV_MISSION_UNSUPPORTED,
_type);

Expand Down Expand Up @@ -341,11 +341,11 @@ void MAVLinkMissionTransfer::UploadWorkItem::send_mission_item()

mavlink_message_t message;
mavlink_msg_mission_item_int_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
_next_sequence,
_items[_next_sequence].frame,
_items[_next_sequence].command,
Expand Down Expand Up @@ -512,11 +512,11 @@ void MAVLinkMissionTransfer::DownloadWorkItem::request_list()
{
mavlink_message_t message;
mavlink_msg_mission_request_list_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
_type);

if (!_sender.send_message(message)) {
Expand All @@ -532,11 +532,11 @@ void MAVLinkMissionTransfer::DownloadWorkItem::request_item()
{
mavlink_message_t message;
mavlink_msg_mission_request_int_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
_next_sequence,
_type);

Expand All @@ -553,11 +553,11 @@ void MAVLinkMissionTransfer::DownloadWorkItem::send_ack_and_finish()
{
mavlink_message_t message;
mavlink_msg_mission_ack_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
MAV_MISSION_ACCEPTED,
_type);

Expand All @@ -574,11 +574,11 @@ void MAVLinkMissionTransfer::DownloadWorkItem::send_cancel_and_finish()
{
mavlink_message_t message;
mavlink_msg_mission_ack_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
MAV_MISSION_OPERATION_CANCELLED,
_type);

Expand Down Expand Up @@ -728,11 +728,11 @@ void MAVLinkMissionTransfer::ClearWorkItem::send_clear()
{
mavlink_message_t message;
mavlink_msg_mission_clear_all_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
_type);

if (!_sender.send_message(message)) {
Expand Down Expand Up @@ -880,11 +880,11 @@ void MAVLinkMissionTransfer::SetCurrentWorkItem::send_current_mission_item()
{
mavlink_message_t message;
mavlink_msg_mission_set_current_pack(
_sender.own_address.system_id,
_sender.own_address.component_id,
_sender.get_own_system_id(),
_sender.get_own_component_id(),
&message,
_sender.target_address.system_id,
_sender.target_address.component_id,
_sender.get_system_id(),
MAV_COMP_ID_AUTOPILOT1,
_current);

if (!_sender.send_message(message)) {
Expand Down
10 changes: 4 additions & 6 deletions src/core/mavlink_mission_transfer.h
Expand Up @@ -16,14 +16,12 @@ namespace mavsdk {

class Sender {
public:
Sender(MAVLinkAddress& new_own_address, MAVLinkAddress& new_target_address) :
own_address(new_own_address),
target_address(new_target_address)
{}
Sender() = default;
virtual ~Sender() = default;
virtual bool send_message(mavlink_message_t& message) = 0;
MAVLinkAddress& own_address;
MAVLinkAddress& target_address;
virtual uint8_t get_own_system_id() const = 0;
virtual uint8_t get_own_component_id() const = 0;
virtual uint8_t get_system_id() const = 0;
};

class MAVLinkMissionTransfer {
Expand Down

0 comments on commit 5a9289e

Please sign in to comment.