forked from Archive/PX4-Autopilot
Formatting and some ftp drive-by
This commit is contained in:
parent
dfe71b615c
commit
f84e18f27a
|
@ -123,27 +123,41 @@ public:
|
|||
/**
|
||||
* Display the mavlink status.
|
||||
*/
|
||||
void status();
|
||||
void status();
|
||||
|
||||
static int stream(int argc, char *argv[]);
|
||||
static int stream(int argc, char *argv[]);
|
||||
|
||||
static int instance_count();
|
||||
static int instance_count();
|
||||
|
||||
static Mavlink *new_instance();
|
||||
static Mavlink *new_instance();
|
||||
|
||||
static Mavlink *get_instance(unsigned instance);
|
||||
static Mavlink *get_instance(unsigned instance);
|
||||
|
||||
static Mavlink *get_instance_for_device(const char *device_name);
|
||||
static Mavlink *get_instance_for_device(const char *device_name);
|
||||
|
||||
static int destroy_all_instances();
|
||||
static int destroy_all_instances();
|
||||
|
||||
static bool instance_exists(const char *device_name, Mavlink *self);
|
||||
static bool instance_exists(const char *device_name, Mavlink *self);
|
||||
|
||||
static void forward_message(mavlink_message_t *msg, Mavlink *self);
|
||||
static void forward_message(mavlink_message_t *msg, Mavlink *self);
|
||||
|
||||
static int get_uart_fd(unsigned index);
|
||||
static int get_uart_fd(unsigned index);
|
||||
|
||||
int get_uart_fd();
|
||||
int get_uart_fd();
|
||||
|
||||
/**
|
||||
* Get the MAVLink system id.
|
||||
*
|
||||
* @return The system ID of this vehicle
|
||||
*/
|
||||
int get_system_id();
|
||||
|
||||
/**
|
||||
* Get the MAVLink component id.
|
||||
*
|
||||
* @return The component ID of this vehicle
|
||||
*/
|
||||
int get_component_id();
|
||||
|
||||
const char *_device_name;
|
||||
|
||||
|
@ -153,30 +167,30 @@ public:
|
|||
MAVLINK_MODE_CAMERA
|
||||
};
|
||||
|
||||
void set_mode(enum MAVLINK_MODE);
|
||||
enum MAVLINK_MODE get_mode() { return _mode; }
|
||||
void set_mode(enum MAVLINK_MODE);
|
||||
enum MAVLINK_MODE get_mode() { return _mode; }
|
||||
|
||||
bool get_hil_enabled() { return _hil_enabled; }
|
||||
bool get_hil_enabled() { return _hil_enabled; }
|
||||
|
||||
bool get_use_hil_gps() { return _use_hil_gps; }
|
||||
bool get_use_hil_gps() { return _use_hil_gps; }
|
||||
|
||||
bool get_flow_control_enabled() { return _flow_control_enabled; }
|
||||
bool get_flow_control_enabled() { return _flow_control_enabled; }
|
||||
|
||||
bool get_forwarding_on() { return _forwarding_on; }
|
||||
bool get_forwarding_on() { return _forwarding_on; }
|
||||
|
||||
/**
|
||||
* Handle waypoint related messages.
|
||||
*/
|
||||
void mavlink_wpm_message_handler(const mavlink_message_t *msg);
|
||||
void mavlink_wpm_message_handler(const mavlink_message_t *msg);
|
||||
|
||||
static int start_helper(int argc, char *argv[]);
|
||||
static int start_helper(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Handle parameter related messages.
|
||||
*/
|
||||
void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg);
|
||||
void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg);
|
||||
|
||||
void get_mavlink_mode_and_state(struct vehicle_status_s *status, struct position_setpoint_triplet_s *pos_sp_triplet, uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode);
|
||||
void get_mavlink_mode_and_state(struct vehicle_status_s *status, struct position_setpoint_triplet_s *pos_sp_triplet, uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode);
|
||||
|
||||
/**
|
||||
* Enable / disable Hardware in the Loop simulation mode.
|
||||
|
@ -186,90 +200,93 @@ public:
|
|||
* requested change could not be made or was
|
||||
* redundant.
|
||||
*/
|
||||
int set_hil_enabled(bool hil_enabled);
|
||||
int set_hil_enabled(bool hil_enabled);
|
||||
|
||||
MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic);
|
||||
MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic);
|
||||
|
||||
int get_instance_id();
|
||||
int get_instance_id();
|
||||
|
||||
/**
|
||||
* Enable / disable hardware flow control.
|
||||
*
|
||||
* @param enabled True if hardware flow control should be enabled
|
||||
*/
|
||||
int enable_flow_control(bool enabled);
|
||||
int enable_flow_control(bool enabled);
|
||||
|
||||
mavlink_channel_t get_channel();
|
||||
const mavlink_channel_t get_channel();
|
||||
|
||||
bool _task_should_exit; /**< if true, mavlink task should exit */
|
||||
bool _task_should_exit; /**< if true, mavlink task should exit */
|
||||
|
||||
int get_mavlink_fd() { return _mavlink_fd; }
|
||||
int get_mavlink_fd() { return _mavlink_fd; }
|
||||
|
||||
|
||||
/* Functions for waiting to start transmission until message received. */
|
||||
void set_has_received_messages(bool received_messages) { _received_messages = received_messages; }
|
||||
bool get_has_received_messages() { return _received_messages; }
|
||||
void set_wait_to_transmit(bool wait) { _wait_to_transmit = wait; }
|
||||
bool get_wait_to_transmit() { return _wait_to_transmit; }
|
||||
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
|
||||
void set_has_received_messages(bool received_messages) { _received_messages = received_messages; }
|
||||
bool get_has_received_messages() { return _received_messages; }
|
||||
void set_wait_to_transmit(bool wait) { _wait_to_transmit = wait; }
|
||||
bool get_wait_to_transmit() { return _wait_to_transmit; }
|
||||
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
|
||||
|
||||
bool message_buffer_write(void *ptr, int size);
|
||||
|
||||
protected:
|
||||
Mavlink *next;
|
||||
Mavlink *next;
|
||||
|
||||
private:
|
||||
int _instance_id;
|
||||
int _instance_id;
|
||||
|
||||
int _mavlink_fd;
|
||||
bool _task_running;
|
||||
int _mavlink_fd;
|
||||
bool _task_running;
|
||||
|
||||
/* states */
|
||||
bool _hil_enabled; /**< Hardware In the Loop mode */
|
||||
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
|
||||
bool _is_usb_uart; /**< Port is USB */
|
||||
bool _wait_to_transmit; /**< Wait to transmit until received messages. */
|
||||
bool _received_messages; /**< Whether we've received valid mavlink messages. */
|
||||
bool _hil_enabled; /**< Hardware In the Loop mode */
|
||||
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
|
||||
bool _is_usb_uart; /**< Port is USB */
|
||||
bool _wait_to_transmit; /**< Wait to transmit until received messages. */
|
||||
bool _received_messages; /**< Whether we've received valid mavlink messages. */
|
||||
|
||||
unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */
|
||||
unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */
|
||||
|
||||
MavlinkOrbSubscription *_subscriptions;
|
||||
MavlinkStream *_streams;
|
||||
MavlinkOrbSubscription *_subscriptions;
|
||||
MavlinkStream *_streams;
|
||||
|
||||
orb_advert_t _mission_pub;
|
||||
struct mission_s mission;
|
||||
MAVLINK_MODE _mode;
|
||||
orb_advert_t _mission_pub;
|
||||
struct mission_s mission;
|
||||
MAVLINK_MODE _mode;
|
||||
|
||||
uint8_t _mavlink_wpm_comp_id;
|
||||
mavlink_channel_t _channel;
|
||||
uint8_t _mavlink_wpm_comp_id;
|
||||
mavlink_channel_t _channel;
|
||||
|
||||
struct mavlink_logbuffer _logbuffer;
|
||||
unsigned int _total_counter;
|
||||
unsigned int _total_counter;
|
||||
|
||||
pthread_t _receive_thread;
|
||||
pthread_t _receive_thread;
|
||||
|
||||
/* Allocate storage space for waypoints */
|
||||
mavlink_wpm_storage _wpm_s;
|
||||
mavlink_wpm_storage *_wpm;
|
||||
mavlink_wpm_storage _wpm_s;
|
||||
mavlink_wpm_storage *_wpm;
|
||||
|
||||
bool _verbose;
|
||||
bool _forwarding_on;
|
||||
bool _passing_on;
|
||||
int _uart_fd;
|
||||
int _baudrate;
|
||||
int _datarate;
|
||||
bool _verbose;
|
||||
bool _forwarding_on;
|
||||
bool _passing_on;
|
||||
bool _ftp_on;
|
||||
int _uart_fd;
|
||||
int _baudrate;
|
||||
int _datarate;
|
||||
|
||||
/**
|
||||
* If the queue index is not at 0, the queue sending
|
||||
* logic will send parameters from the current index
|
||||
* to len - 1, the end of the param list.
|
||||
*/
|
||||
unsigned int _mavlink_param_queue_index;
|
||||
unsigned int _mavlink_param_queue_index;
|
||||
|
||||
bool mavlink_link_termination_allowed;
|
||||
bool mavlink_link_termination_allowed;
|
||||
|
||||
char *_subscribe_to_stream;
|
||||
float _subscribe_to_stream_rate;
|
||||
char *_subscribe_to_stream;
|
||||
float _subscribe_to_stream_rate;
|
||||
|
||||
bool _flow_control_enabled;
|
||||
bool _flow_control_enabled;
|
||||
|
||||
struct mavlink_message_buffer {
|
||||
int write_ptr;
|
||||
|
@ -277,11 +294,12 @@ private:
|
|||
int size;
|
||||
char *data;
|
||||
};
|
||||
mavlink_message_buffer _message_buffer;
|
||||
|
||||
pthread_mutex_t _message_buffer_mutex;
|
||||
mavlink_message_buffer _message_buffer;
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
pthread_mutex_t _message_buffer_mutex;
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
/**
|
||||
* Send one parameter.
|
||||
|
@ -289,7 +307,7 @@ private:
|
|||
* @param param The parameter id to send.
|
||||
* @return zero on success, nonzero on failure.
|
||||
*/
|
||||
int mavlink_pm_send_param(param_t param);
|
||||
int mavlink_pm_send_param(param_t param);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by index.
|
||||
|
@ -297,7 +315,7 @@ private:
|
|||
* @param index The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int mavlink_pm_send_param_for_index(uint16_t index);
|
||||
int mavlink_pm_send_param_for_index(uint16_t index);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by name.
|
||||
|
@ -305,14 +323,14 @@ private:
|
|||
* @param name The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int mavlink_pm_send_param_for_name(const char *name);
|
||||
int mavlink_pm_send_param_for_name(const char *name);
|
||||
|
||||
/**
|
||||
* Send a queue of parameters, one parameter per function call.
|
||||
*
|
||||
* @return zero on success, nonzero on failure
|
||||
*/
|
||||
int mavlink_pm_queued_send(void);
|
||||
int mavlink_pm_queued_send(void);
|
||||
|
||||
/**
|
||||
* Start sending the parameter queue.
|
||||
|
@ -322,12 +340,12 @@ private:
|
|||
* mavlink_pm_queued_send().
|
||||
* @see mavlink_pm_queued_send()
|
||||
*/
|
||||
void mavlink_pm_start_queued_send();
|
||||
void mavlink_pm_start_queued_send();
|
||||
|
||||
void mavlink_update_system();
|
||||
void mavlink_update_system();
|
||||
|
||||
void mavlink_waypoint_eventloop(uint64_t now);
|
||||
void mavlink_wpm_send_waypoint_reached(uint16_t seq);
|
||||
void mavlink_waypoint_eventloop(uint64_t now);
|
||||
void mavlink_wpm_send_waypoint_reached(uint16_t seq);
|
||||
void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq);
|
||||
void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq);
|
||||
void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count);
|
||||
|
@ -354,8 +372,6 @@ private:
|
|||
|
||||
int message_buffer_is_empty();
|
||||
|
||||
bool message_buffer_write(void *ptr, int size);
|
||||
|
||||
int message_buffer_get_ptr(void **ptr, bool *is_part);
|
||||
|
||||
void message_buffer_mark_read(int n);
|
||||
|
|
Loading…
Reference in New Issue