Firmware
mavlink_parameters.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
43 #pragma once
44 
45 #include <parameters/param.h>
46 
47 #include "mavlink_bridge_header.h"
48 #include <uORB/uORB.h>
49 #include <uORB/topics/rc_parameter_map.h>
50 #include <uORB/topics/uavcan_parameter_request.h>
51 #include <uORB/topics/parameter_update.h>
52 #include <drivers/drv_hrt.h>
53 
54 class Mavlink;
55 
57 {
58 public:
59  explicit MavlinkParametersManager(Mavlink *mavlink);
61 
66  void send(const hrt_abstime t);
67 
68  unsigned get_size();
69 
70  void handle_message(const mavlink_message_t *msg);
71 
72 private:
73  int _send_all_index;
74 
75  /* do not allow top copying this class */
78 
79 protected:
82  bool send_one();
83 
87  bool send_params();
88 
92  bool send_uavcan();
93 
97  bool send_untransmitted();
98 
99  int send_param(param_t param, int component_id = -1);
100 
101  // Item of a single-linked list to store requested uavcan parameters
103  uavcan_parameter_request_s req;
104  struct _uavcan_open_request_list_item *next;
105  };
106 
111 
115  void enque_uavcan_request(uavcan_parameter_request_s *req);
116 
120  void dequeue_uavcan_request();
121 
125 
126  orb_advert_t _rc_param_map_pub;
127  struct rc_parameter_map_s _rc_param_map;
128 
129  orb_advert_t _uavcan_parameter_request_pub;
130  int _uavcan_parameter_value_sub;
131  int _mavlink_parameter_sub;
132  hrt_abstime _param_update_time;
133  int _param_update_index;
134 
135  Mavlink *_mavlink;
136 };
bool _uavcan_waiting_for_request_response
We have reqested a parameter and wait for the response.
Definition: mavlink_parameters.h:123
void request_next_uavcan_parameter()
Request the next uavcan parameter.
Definition: mavlink_parameters.cpp:605
void enque_uavcan_request(uavcan_parameter_request_s *req)
Enqueue one uavcan parameter reqest.
Definition: mavlink_parameters.cpp:622
uint16_t _uavcan_queued_request_items
Number of stored parameter requests currently in the list.
Definition: mavlink_parameters.h:124
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
bool send_uavcan()
Send UAVCAN params.
Definition: mavlink_parameters.cpp:408
High-resolution timer with callouts and timekeeping.
_uavcan_open_request_list_item * _uavcan_open_request_list
Pointer to the first item in the linked list.
Definition: mavlink_parameters.h:122
Global flash based parameter store.
bool send_params()
Handle any open param send transfer.
Definition: mavlink_parameters.cpp:331
bool send_untransmitted()
Send untransmitted params.
Definition: mavlink_parameters.cpp:348
API for the uORB lightweight object broker.
void send(const hrt_abstime t)
Handle sending of messages.
Definition: mavlink_parameters.cpp:312
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Definition: mavlink_parameters.h:56
bool send_one()
send a single param if a PARAM_REQUEST_LIST is in progress
Definition: mavlink_parameters.cpp:471
void dequeue_uavcan_request()
Drop the first reqest from the list.
Definition: mavlink_parameters.cpp:651
uint32_t param_t
Parameter handle.
Definition: param.h:98