mavlink / c_uart_interface_example

Simple MAVLink to UART interface example for *nix systems
264 stars 257 forks source link

current_setpoint->current_setpoint.data #35

Closed SMP33 closed 3 years ago

SMP33 commented 3 years ago

Fix error in autopilot_interface.cpp:226

autopilot_interface.cpp: In member function ‘void Autopilot_Interface::update_setpoint(mavlink_set_position_target_local_ned_t)’: autopilot_interface.cpp:226:21: error: no match for ‘operator=’ (operand types are ‘Autopilot_Interface::’ and ‘mavlink_set_position_target_local_ned_t {aka __mavlink_set_position_target_local_ned_t}’) current_setpoint = setpoint;

Change to: current_setpoint.data = setpoint;

VirtualBox_Ubuntu_11_08_2020_12_42_13

Commit has been tested with

make px4_sitl jmavsim ./mavlink_control -u 127.0.0.1 VirtualBox_Ubuntu_11_08_2020_13_21_51

heleidsn commented 3 years ago

It's good to fix my problem. Thanks.

wakecoder commented 3 years ago

Shouldn't this acquire the lock before setting current_setpoint.data? That was the point of the previous PR (#34)that accidentally introduced this error. It should be:

std::lock_guard<std::mutex> lock(current_setpoint.mutex);
current_setpoint.data = setpoint;

If you want me to put out a PR, I can but it may be easier to just update this one since it isn't merged yet.

SMP33 commented 3 years ago

Shouldn't this acquire the lock before setting current_setpoint.data? That was the point of the previous PR (#34)that accidentally introduced this error. It should be:

std::lock_guard<std::mutex> lock(current_setpoint.mutex);
current_setpoint.data = setpoint;

If you want me to put out a PR, I can but it may be easier to just update this one since it isn't merged yet.

I'm wildly sorry. I fixed the compilation error and completely forgot about the mutex. I have now added the line std :: lock_guard lock (current_setpoint.mutex); in second commit.