mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
GCS_MAVLink: factor out a send_banner
This commit is contained in:
parent
b5d234aa64
commit
1544a92f8b
@ -263,6 +263,7 @@ protected:
|
|||||||
void handle_param_set(mavlink_message_t *msg);
|
void handle_param_set(mavlink_message_t *msg);
|
||||||
void handle_param_request_list(mavlink_message_t *msg);
|
void handle_param_request_list(mavlink_message_t *msg);
|
||||||
void handle_param_request_read(mavlink_message_t *msg);
|
void handle_param_request_read(mavlink_message_t *msg);
|
||||||
|
virtual bool params_ready() const { return true; }
|
||||||
|
|
||||||
void handle_common_gps_message(mavlink_message_t *msg);
|
void handle_common_gps_message(mavlink_message_t *msg);
|
||||||
void handle_common_rally_message(mavlink_message_t *msg);
|
void handle_common_rally_message(mavlink_message_t *msg);
|
||||||
@ -282,6 +283,8 @@ protected:
|
|||||||
void handle_send_autopilot_version(const mavlink_message_t *msg);
|
void handle_send_autopilot_version(const mavlink_message_t *msg);
|
||||||
MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet);
|
||||||
|
|
||||||
|
virtual void send_banner();
|
||||||
|
|
||||||
void handle_device_op_read(mavlink_message_t *msg);
|
void handle_device_op_read(mavlink_message_t *msg);
|
||||||
void handle_device_op_write(mavlink_message_t *msg);
|
void handle_device_op_write(mavlink_message_t *msg);
|
||||||
|
|
||||||
|
@ -1959,6 +1959,22 @@ void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t *msg)
|
|||||||
send_autopilot_version(fwver.major, fwver.minor, fwver.patch, fwver.fw_type);
|
send_autopilot_version(fwver.major, fwver.minor, fwver.patch, fwver.fw_type);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void GCS_MAVLINK::send_banner()
|
||||||
|
{
|
||||||
|
// mark the firmware version in the tlog
|
||||||
|
const AP_FWVersion &fwver = get_fwver();
|
||||||
|
send_text(MAV_SEVERITY_INFO, fwver.fw_string);
|
||||||
|
|
||||||
|
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
||||||
|
send_text(MAV_SEVERITY_INFO, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// send system ID if we can
|
||||||
|
char sysid[40];
|
||||||
|
if (hal.util->get_system_id(sysid)) {
|
||||||
|
send_text(MAV_SEVERITY_INFO, sysid);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
|
||||||
|
@ -188,22 +188,15 @@ void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg, bool save)
|
|||||||
|
|
||||||
void GCS_MAVLINK::handle_param_request_list(mavlink_message_t *msg)
|
void GCS_MAVLINK::handle_param_request_list(mavlink_message_t *msg)
|
||||||
{
|
{
|
||||||
|
if (!params_ready()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
mavlink_param_request_list_t packet;
|
mavlink_param_request_list_t packet;
|
||||||
mavlink_msg_param_request_list_decode(msg, &packet);
|
mavlink_msg_param_request_list_decode(msg, &packet);
|
||||||
|
|
||||||
// mark the firmware version in the tlog
|
// requesting parameters is a convenient way to get extra information
|
||||||
const AP_FWVersion &fwver = get_fwver();
|
send_banner();
|
||||||
send_text(MAV_SEVERITY_INFO, fwver.fw_string);
|
|
||||||
|
|
||||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
|
||||||
send_text(MAV_SEVERITY_INFO, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// send system ID if we can
|
|
||||||
char sysid[40];
|
|
||||||
if (hal.util->get_system_id(sysid)) {
|
|
||||||
send_text(MAV_SEVERITY_INFO, sysid);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Start sending parameters - next call to ::update will kick the first one out
|
// Start sending parameters - next call to ::update will kick the first one out
|
||||||
_queued_parameter = AP_Param::first(&_queued_parameter_token, &_queued_parameter_type);
|
_queued_parameter = AP_Param::first(&_queued_parameter_token, &_queued_parameter_type);
|
||||||
|
Loading…
Reference in New Issue
Block a user