mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_DroneCAN: improve get/set param comments
This commit is contained in:
parent
e614a1c58c
commit
6fe31396d9
@ -1264,6 +1264,11 @@ void AP_DroneCAN::handle_debug(const CanardRxTransfer& transfer, const uavcan_pr
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
/*
|
||||
send any queued request to get/set parameter
|
||||
called from loop
|
||||
*/
|
||||
void AP_DroneCAN::send_parameter_request()
|
||||
{
|
||||
WITH_SEMAPHORE(_param_sem);
|
||||
@ -1274,12 +1279,16 @@ void AP_DroneCAN::send_parameter_request()
|
||||
param_request_sent = true;
|
||||
}
|
||||
|
||||
/*
|
||||
set named float parameter on node
|
||||
*/
|
||||
bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, float value, ParamGetSetFloatCb *cb)
|
||||
{
|
||||
WITH_SEMAPHORE(_param_sem);
|
||||
|
||||
// fail if waiting for any previous get/set request
|
||||
if (param_int_cb != nullptr ||
|
||||
param_float_cb != nullptr) {
|
||||
//busy
|
||||
return false;
|
||||
}
|
||||
param_getset_req.index = 0;
|
||||
@ -1292,12 +1301,16 @@ bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, float
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
set named integer parameter on node
|
||||
*/
|
||||
bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32_t value, ParamGetSetIntCb *cb)
|
||||
{
|
||||
WITH_SEMAPHORE(_param_sem);
|
||||
|
||||
// fail if waiting for any previous get/set request
|
||||
if (param_int_cb != nullptr ||
|
||||
param_float_cb != nullptr) {
|
||||
//busy
|
||||
return false;
|
||||
}
|
||||
param_getset_req.index = 0;
|
||||
@ -1310,12 +1323,16 @@ bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
get named float parameter on node
|
||||
*/
|
||||
bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetFloatCb *cb)
|
||||
{
|
||||
WITH_SEMAPHORE(_param_sem);
|
||||
|
||||
// fail if waiting for any previous get/set request
|
||||
if (param_int_cb != nullptr ||
|
||||
param_float_cb != nullptr) {
|
||||
//busy
|
||||
return false;
|
||||
}
|
||||
param_getset_req.index = 0;
|
||||
@ -1327,12 +1344,16 @@ bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, Param
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
get named integer parameter on node
|
||||
*/
|
||||
bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetIntCb *cb)
|
||||
{
|
||||
WITH_SEMAPHORE(_param_sem);
|
||||
|
||||
// fail if waiting for any previous get/set request
|
||||
if (param_int_cb != nullptr ||
|
||||
param_float_cb != nullptr) {
|
||||
//busy
|
||||
return false;
|
||||
}
|
||||
param_getset_req.index = 0;
|
||||
|
@ -95,7 +95,9 @@ public:
|
||||
// THIS IS NOT A THREAD SAFE API!
|
||||
void send_reboot_request(uint8_t node_id);
|
||||
|
||||
// set param value
|
||||
// get or set param value
|
||||
// returns true on success, false on failure
|
||||
// failures occur when waiting on node to respond to previous get or set request
|
||||
bool set_parameter_on_node(uint8_t node_id, const char *name, float value, ParamGetSetFloatCb *cb);
|
||||
bool set_parameter_on_node(uint8_t node_id, const char *name, int32_t value, ParamGetSetIntCb *cb);
|
||||
bool get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetFloatCb *cb);
|
||||
@ -151,27 +153,27 @@ private:
|
||||
// send notify vehicle state
|
||||
void notify_state_send();
|
||||
|
||||
// send parameter get/set request
|
||||
// send queued parameter get/set request. called from loop
|
||||
void send_parameter_request();
|
||||
|
||||
// send parameter save request
|
||||
// send queued parameter save request. called from loop
|
||||
void send_parameter_save_request();
|
||||
|
||||
// periodic logging
|
||||
void logging();
|
||||
|
||||
// set parameter on a node
|
||||
ParamGetSetIntCb *param_int_cb;
|
||||
ParamGetSetFloatCb *param_float_cb;
|
||||
bool param_request_sent = true;
|
||||
HAL_Semaphore _param_sem;
|
||||
uint8_t param_request_node_id;
|
||||
// get parameter on a node
|
||||
ParamGetSetIntCb *param_int_cb; // latest get param request callback function (for integers)
|
||||
ParamGetSetFloatCb *param_float_cb; // latest get param request callback function (for floats)
|
||||
bool param_request_sent = true; // true after a param request has been sent, false when queued to be sent
|
||||
HAL_Semaphore _param_sem; // semaphore protecting this block of variables
|
||||
uint8_t param_request_node_id; // node id of most recent get param request
|
||||
|
||||
// save parameters on a node
|
||||
ParamSaveCb *save_param_cb;
|
||||
bool param_save_request_sent = true;
|
||||
HAL_Semaphore _param_save_sem;
|
||||
uint8_t param_save_request_node_id;
|
||||
ParamSaveCb *save_param_cb; // latest save param request callback function
|
||||
bool param_save_request_sent = true; // true after a save param request has been sent, false when queued to be sent
|
||||
HAL_Semaphore _param_save_sem; // semaphore protecting this block of variables
|
||||
uint8_t param_save_request_node_id; // node id of most recent save param request
|
||||
|
||||
// UAVCAN parameters
|
||||
AP_Int8 _dronecan_node;
|
||||
|
Loading…
Reference in New Issue
Block a user