diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 4e0fec940cf7edd4e8a13c9a09da4117a17150d8..f5382b3c5640ca169cd8cab5e81c8c347590e782 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -123,15 +123,13 @@ WindowsBuild { # MacBuild | LinuxBuild { - QMAKE_CXXFLAGS_WARN_ON += -Wall -} - -MacBuild { - QMAKE_CXXFLAGS_WARN_ON += -Werror + QMAKE_CXXFLAGS_WARN_ON += -Wall \ + -Werror } WindowsBuild { QMAKE_CXXFLAGS_WARN_ON += /W3 \ + /WX \ /wd4996 \ # silence warnings about deprecated strcpy and whatnot /wd4290 # ignore exception specifications } diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 35c06b26097b344c8a7003b22bbbc746029a949e..1703c2342c3f1c92e6c82c78cd994eb3e0ed09fa 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -483,6 +483,7 @@ void MAVLinkSimulationLink::mainloop() #ifdef MAVLINK_ENABLED_PIXHAWK mavlink_pattern_detected_t detected; detected.confidence = 5.0f; + detected.type = 0; // compiler confused into thinking type is used unitialized, bogus init to silence if (detectionCounter == 10) { char fileName[] = "patterns/face5.png"; diff --git a/src/comm/MAVLinkSimulationWaypointPlanner.cc b/src/comm/MAVLinkSimulationWaypointPlanner.cc index a53f17c5d974f930d15017ef95f894b3b6f6293e..d855697419d9bb74d35f23c0c4ffb2e22cc3041b 100644 --- a/src/comm/MAVLinkSimulationWaypointPlanner.cc +++ b/src/comm/MAVLinkSimulationWaypointPlanner.cc @@ -523,38 +523,29 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq) if(seq < waypoints->size()) { mavlink_mission_item_t *cur = waypoints->at(seq); - mavlink_message_t msg; - mavlink_set_local_position_setpoint_t PControlSetPoint; - // send new set point to local IMU - if (cur->frame == 1) { - PControlSetPoint.target_system = systemid; - PControlSetPoint.target_component = MAV_COMP_ID_IMU; - PControlSetPoint.x = cur->x; - PControlSetPoint.y = cur->y; - PControlSetPoint.z = cur->z; - PControlSetPoint.yaw = cur->param4; + if (cur->frame == MAV_FRAME_LOCAL_NED || cur->frame == MAV_FRAME_LOCAL_ENU) { + mavlink_message_t msg; + mavlink_set_local_position_setpoint_t PControlSetPoint; - mavlink_msg_set_local_position_setpoint_encode(systemid, compid, &msg, &PControlSetPoint); - link->sendMAVLinkMessage(&msg); - - - } else { - //if (verbose) qDebug("No new set point sent to IMU because the new waypoint %u had no local coordinates\n", cur->seq); PControlSetPoint.target_system = systemid; PControlSetPoint.target_component = MAV_COMP_ID_IMU; PControlSetPoint.x = cur->x; PControlSetPoint.y = cur->y; PControlSetPoint.z = cur->z; PControlSetPoint.yaw = cur->param4; - + PControlSetPoint.coordinate_frame = cur->frame; + mavlink_msg_set_local_position_setpoint_encode(systemid, compid, &msg, &PControlSetPoint); link->sendMAVLinkMessage(&msg); emit messageSent(msg); + + uint64_t now = QGC::groundTimeMilliseconds(); + timestamp_last_send_setpoint = now; + } else if (verbose) { + qDebug("No new set point sent to IMU because the new waypoint %u had no local coordinates\n", cur->seq); } - uint64_t now = QGC::groundTimeMilliseconds(); - timestamp_last_send_setpoint = now; } }