49 uint16_t bytes_allowed;
60 count = bytes_allowed / (MAVLINK_MSG_ID_PARAM_VALUE_LEN +
packet_overhead());
81 mavlink_msg_param_value_send(
105 if (
_port ==
nullptr) {
113 if (
chan == MAVLINK_COMM_0) {
129 mavlink_request_data_stream_t packet;
130 mavlink_msg_request_data_stream_decode(msg, &packet);
134 if (packet.start_stop == 0)
136 else if (packet.start_stop == 1)
137 freq = packet.req_message_rate;
141 AP_Int16 *rate =
nullptr;
142 switch (packet.req_stream_id) {
143 case MAV_DATA_STREAM_ALL:
153 case MAV_DATA_STREAM_RAW_SENSORS:
156 case MAV_DATA_STREAM_EXTENDED_STATUS:
159 case MAV_DATA_STREAM_RC_CHANNELS:
162 case MAV_DATA_STREAM_RAW_CONTROLLER:
165 case MAV_DATA_STREAM_POSITION:
168 case MAV_DATA_STREAM_EXTRA1:
171 case MAV_DATA_STREAM_EXTRA2:
174 case MAV_DATA_STREAM_EXTRA3:
179 if (rate !=
nullptr) {
181 rate->set_and_save_ifchanged(freq);
194 mavlink_param_request_list_t packet;
195 mavlink_msg_param_request_list_decode(msg, &packet);
213 mavlink_param_request_read_t packet;
214 mavlink_msg_param_request_read_decode(msg, &packet);
240 mavlink_param_set_t packet;
241 mavlink_msg_param_set_decode(msg, &packet);
258 vp->
set_float(packet.param_value, var_type);
267 bool force_save = !
is_equal(packet.param_value, old_value);
270 vp->
save(force_save);
273 if (DataFlash !=
nullptr) {
284 float rate = (uint8_t)
streamRates[stream_num].
get();
292 bool is_streaming =
false;
293 for (uint8_t i=0; i<stream_num; i++) {
329 if ((1U<<i) & mavlink_active) {
330 const mavlink_channel_t _chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
332 mavlink_msg_param_value_send(
344 if (dataflash !=
nullptr) {
433 mavlink_msg_param_value_send(
444 switch (msg->msgid) {
445 case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
448 case MAVLINK_MSG_ID_PARAM_SET:
451 case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
AP_Param::ParamToken _queued_parameter_token
void handle_param_set(mavlink_message_t *msg)
virtual void send_banner()
uint16_t _queued_parameter_index
AP_Param token for.
static uint8_t chan_is_streaming
bool stream_trigger(enum streams stream_num)
static ObjectBuffer< pending_param_reply > param_replies
AP_Param * _queued_parameter
next parameter to
static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype)
static uint32_t reserve_param_space_start_ms
Interface definition for the various Ground Control System.
void send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
void Log_Write_Parameter(const char *name, float value)
static AP_Param * find(const char *name, enum ap_var_type *ptype)
float adjust_rate_for_stream_trigger(enum streams stream_num)
static int comm_get_txspace(mavlink_channel_t chan)
void handle_common_param_message(mavlink_message_t *msg)
void handle_request_data_stream(mavlink_message_t *msg)
enum ap_var_type _queued_parameter_type
type of the next
virtual bool usb_connected(void)=0
static uint8_t active_channel_mask(void)
static uint16_t count_parameters(void)
#define HAVE_PAYLOAD_SPACE(chan, id)
static ObjectBuffer< pending_param_request > param_requests
void send_queued_parameters(void)
void handle_param_request_list(mavlink_message_t *msg)
void send_parameter_reply(void)
char param_name[AP_MAX_NAME_SIZE+1]
static AP_Param * first(ParamToken *token, enum ap_var_type *ptype)
static DataFlash_Class * instance(void)
void set_float(float value, enum ap_var_type var_type)
uint16_t _queued_parameter_count
saved count of
void queued_param_send()
Send the next pending parameter, called from deferred message handling code.
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual bool persist_streamrates() const
AP_HAL::UARTDriver * _port
The stream we are communicating over.
virtual void register_io_process(AP_HAL::MemberProc)=0
float cast_to_float(enum ap_var_type type) const
cast a variable to a float given its type
uint8_t stream_ticks[NUM_STREAMS]
DataFlash_Class DataFlash
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
virtual enum flow_control get_flow_control(void)
void handle_param_request_read(mavlink_message_t *msg)
char param_name[AP_MAX_NAME_SIZE+1]
void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const
virtual bool params_ready() const
uint32_t _queued_parameter_send_time_ms
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
uint8_t mav_var_type(enum ap_var_type t)
bool save(bool force_save=false)
uint8_t packet_overhead(void) const
void param_io_timer(void)
void send_message(enum ap_message id)
static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token)
static bool param_timer_registered
static uint8_t mavlink_active
AP_Int16 streamRates[NUM_STREAMS]
AP_HAL::Scheduler * scheduler
#define MAVLINK_COMM_NUM_BUFFERS