comms package#
Submodules#
comms.listener module#
- class comms.listener.Listener#
Bases:
Node
This node is responsible for listening for ardupilot data through the MAVLink protocol, and publishing them to the ROS network.
- fetch_from_ardupilot()#
Fetches data from ardupilot based on the specified message types (or keys)
- get_from_ardu_dict(types) dict #
Determines what keys are available on the MAVLink connection
- is_dict_full()#
Checks if each entry in the dictionary has been filled.
- publish_to_topic()#
Publishes the specified topics to the ROS network
- comms.listener.main(args=None)#
comms.mavlink module#
- class comms.mavlink.MAVLink(simulation=False)#
Bases:
object
This class works as an API for MAVLink connections. It is responsible for establishing and managing the protocol.
- autotune(axis=0)#
Sends command to autotune a single axis.
- get_port(simulation) str #
Decides what port to use for MAVLink connection.
- listen(**kwargs) dict #
Listen to the MAVLink connection for the package that matches the arguments.
- pitch(pwm)#
Sends pitch control signal.
- roll(pwm)#
Sends roll control signal.
- throttle(pwm)#
Sends throttle control signal.
- wait_for_heartbeat()#
This function waits until a connection on MAVLink is established, signaled with a so called ‘heartbeat’ from the flight controller.
- yaw(pwm)#
Sends yaw control signal.
comms.sender module#
- class comms.sender.Sender#
Bases:
Node
This node is responsible for sending data through the MAVLink protocol to the ardupilot
- autotune()#
Used to decide which axis to autotune.
- received_joystick(msg)#
Called when receiving new values from the ‘joystick’ topic.
- send_pwm_values()#
Sends control signals to flight controller through the MAVLink connection.
- comms.sender.main(args=None)#