Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

core: move sending heartbeats to Mavsdk class #1244

Merged
merged 1 commit into from
Oct 26, 2020

Conversation

julianoes
Copy link
Collaborator

It actually did not make sense to send heartbeats in the System class because it's the Mavsdk MAVLink node that sends them as broadcast and not per vehicle.

The change was required in order to enable sending heartbeats without first discovering a system. That's needed if MAVSDK is used on a companion or as an autopilot instead of as a ground station.

A few specifics for the change:

  • Move call_every_handler from SystemImpl to MavsdkImpl.
  • Add config option to always send heartbeats, and not just when a vehicle has been discovered.
  • Remove duplicate system_id/component_id vars in MavsdkImpl and use vars in configuration instead.

It actually did not make sense to send heartbeats in the System class
because it's the Mavsdk MAVLink node that sends them as broadcast and
not per vehicle.

The change was required in order to enable sending heartbeats without
first discovering a system. That's needed if MAVSDK is used on a
companion or as an autopilot instead of as a ground station.

A few specifics for the change:
- Move call_every_handler from SystemImpl to MavsdkImpl.
- Add config option to always send heartbeats, and not just when a
  vehicle has been discovered.
- Remove duplicate system_id/component_id vars in MavsdkImpl and use
  vars in configuration instead.
Copy link
Collaborator

@JonasVautherin JonasVautherin left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't that replace the add_remote function used by mavftp?

@@ -98,34 +98,38 @@ void Mavsdk::register_on_timeout(const event_callback_t callback)
_impl->register_on_timeout(callback);
}

Mavsdk::Configuration::Configuration(uint8_t system_id, uint8_t component_id) :
Mavsdk::Configuration::Configuration(
uint8_t system_id, uint8_t component_id, bool always_send_heartbeats) :
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not completely sure about having it as a state boolean. To me, that's about initiating a connection: either you passively listen until you receive heartbeats (and then start sending heartbeats), or you directly start sending heartbeats. In any case, whenever you have started sending heartbeats, that's for the duration of the connection.

Why not exposing start_sending_hearbeat() directly? If that's too much of an implementation detail (e.g. we don't want to mention "hearbeats"), we could call it initiate_connection() (or rather initiate_connections(), because my understanding is that it will send heartbeats on all connections)?

@julianoes
Copy link
Collaborator Author

Shouldn't that replace the add_remote function used by mavftp?

That's a good question. It certainly has to do with it. I think we still need setup_udp_remote() because it actually sends UDP to another port. By default we don't specify a remote port but we only specify the local port to listen to. So I think the "always send heartbeat" option has to be used when setup_udp_remote() is used.

Why not exposing start_sending_hearbeat() directly?

That's' an option, however, I put it into the configuration because it somewhat has to do with it. When you set it up as a ground station you usually do not want to send out the heartbeats. However, when you set it up as an autopilot or companion, then you do want it.

@JonasVautherin
Copy link
Collaborator

When you set it up as a ground station you usually do not want to send out the heartbeats.

I partially agree with that. It actually has to do with discovery and the network topology. Maybe the drone can broadcast heartbeats, maybe it can't. If the drone cannot broadcast, then it cannot be discovered, but the ground station may know how to reach it. Typically, px4-gazebo-headless takes the IP of the ground station as a parameter, because in many situations a broadcast doesn't work. But that's a bit counter-intuitive: usually the server listens on a port, and the client initiates the connection, and px4-gazebo-headless works the other way round (because MAVLink typically expects the "server" to initiate the connection).

But it's just a question of preference in the end, I'm fine with this 👍.

@julianoes
Copy link
Collaborator Author

The case I have here is just a serial connection. In this case it's easy because there is only one destination to send messages 😄. I think we can change this configuration again later, I'm open for improvements.

@julianoes julianoes merged commit 9b56a41 into develop Oct 26, 2020
@julianoes julianoes deleted the pr-mavsdk-heartbeats branch October 26, 2020 16:20
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants