Commit c2c05fbc authored by LM's avatar LM

Fixed compile errors

parent 8db1e34d
...@@ -380,7 +380,6 @@ void MAVLinkSimulationLink::mainloop() ...@@ -380,7 +380,6 @@ void MAVLinkSimulationLink::mainloop()
// Send back new setpoint // Send back new setpoint
mavlink_message_t ret; mavlink_message_t ret;
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw); // spYaw/180.0*M_PI); mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw); // spYaw/180.0*M_PI);
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, spX, spY, spZ,
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret); bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream //add data into datastream
memcpy(stream+streampointer,buffer, bufferlength); memcpy(stream+streampointer,buffer, bufferlength);
......
...@@ -957,7 +957,7 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) ...@@ -957,7 +957,7 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK #ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_local_position_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw/M_PI*180.0); mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw/M_PI*180.0);
sendMessage(msg); sendMessage(msg);
#else #else
Q_UNUSED(x); Q_UNUSED(x);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment