|
|
|
@ -88,6 +88,10 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
@@ -88,6 +88,10 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
|
|
|
|
_parameters_manager(parent), |
|
|
|
|
_mavlink_timesync(parent) |
|
|
|
|
{ |
|
|
|
|
_handle_sens_flow_maxhgt = param_find("SENS_FLOW_MAXHGT"); |
|
|
|
|
_handle_sens_flow_maxr = param_find("SENS_FLOW_MAXR"); |
|
|
|
|
_handle_sens_flow_minhgt = param_find("SENS_FLOW_MINHGT"); |
|
|
|
|
_handle_sens_flow_rot = param_find("SENS_FLOW_ROT"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void |
|
|
|
@ -693,12 +697,12 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
@@ -693,12 +697,12 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
|
|
|
|
|
f.ground_distance_m = flow.distance; |
|
|
|
|
f.quality = flow.quality; |
|
|
|
|
f.sensor_id = flow.sensor_id; |
|
|
|
|
f.max_flow_rate = _param_sens_flow_maxr.get(); |
|
|
|
|
f.min_ground_distance = _param_sens_flow_minhgt.get(); |
|
|
|
|
f.max_ground_distance = _param_sens_flow_maxhgt.get(); |
|
|
|
|
f.max_flow_rate = _param_sens_flow_maxr; |
|
|
|
|
f.min_ground_distance = _param_sens_flow_minhgt; |
|
|
|
|
f.max_ground_distance = _param_sens_flow_maxhgt; |
|
|
|
|
|
|
|
|
|
/* read flow sensor parameters */ |
|
|
|
|
const Rotation flow_rot = (Rotation)_param_sens_flow_rot.get(); |
|
|
|
|
const Rotation flow_rot = (Rotation)_param_sens_flow_rot; |
|
|
|
|
|
|
|
|
|
/* rotate measurements according to parameter */ |
|
|
|
|
float zero_val = 0.0f; |
|
|
|
@ -3339,6 +3343,29 @@ void MavlinkReceiver::start()
@@ -3339,6 +3343,29 @@ void MavlinkReceiver::start()
|
|
|
|
|
pthread_attr_destroy(&receiveloop_attr); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void |
|
|
|
|
MavlinkReceiver::updateParams() |
|
|
|
|
{ |
|
|
|
|
// update parameters from storage
|
|
|
|
|
ModuleParams::updateParams(); |
|
|
|
|
|
|
|
|
|
if (_handle_sens_flow_maxhgt != PARAM_INVALID) { |
|
|
|
|
param_get(_handle_sens_flow_maxhgt, &_param_sens_flow_maxhgt); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_handle_sens_flow_maxr != PARAM_INVALID) { |
|
|
|
|
param_get(_handle_sens_flow_maxr, &_param_sens_flow_maxr); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_handle_sens_flow_minhgt != PARAM_INVALID) { |
|
|
|
|
param_get(_handle_sens_flow_minhgt, &_param_sens_flow_minhgt); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_handle_sens_flow_rot != PARAM_INVALID) { |
|
|
|
|
param_get(_handle_sens_flow_rot, &_param_sens_flow_rot); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void *MavlinkReceiver::start_trampoline(void *context) |
|
|
|
|
{ |
|
|
|
|
MavlinkReceiver *self = reinterpret_cast<MavlinkReceiver *>(context); |
|
|
|
|