Browse Source

vmount initialize params

- fixes CID 199479
sbg
Daniel Agar 7 years ago committed by Lorenz Meier
parent
commit
0931efb3f0
  1. 10
      src/drivers/vmount/input_mavlink.cpp
  2. 4
      src/drivers/vmount/input_mavlink.h

10
src/drivers/vmount/input_mavlink.cpp

@ -178,19 +178,13 @@ InputMavlinkCmdMount::InputMavlinkCmdMount(bool stabilize) @@ -178,19 +178,13 @@ InputMavlinkCmdMount::InputMavlinkCmdMount(bool stabilize)
{
param_t handle = param_find("MAV_SYS_ID");
if (handle == PARAM_INVALID) {
_mav_sys_id = 1;
} else {
if (handle != PARAM_INVALID) {
param_get(handle, &_mav_sys_id);
}
handle = param_find("MAV_COMP_ID");
if (handle == PARAM_INVALID) {
_mav_comp_id = 1;
} else {
if (handle != PARAM_INVALID) {
param_get(handle, &_mav_comp_id);
}
}

4
src/drivers/vmount/input_mavlink.h

@ -98,8 +98,8 @@ private: @@ -98,8 +98,8 @@ private:
orb_advert_t _vehicle_command_ack_pub = nullptr;
bool _stabilize[3] = { false, false, false };
int32_t _mav_sys_id; ///< our mavlink system id
int32_t _mav_comp_id; ///< our mavlink component id
int32_t _mav_sys_id{1}; ///< our mavlink system id
int32_t _mav_comp_id{1}; ///< our mavlink component id
};

Loading…
Cancel
Save