Commit c21cfb7b authored by Don Gagne's avatar Don Gagne

Fix ArduPilot compass cal

parent 687468cf
...@@ -143,18 +143,16 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void) ...@@ -143,18 +143,16 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void)
free(worker_data.z[cur_mag]); free(worker_data.z[cur_mag]);
} }
AutoPilotPlugin* plugin = _vehicle->autopilotPlugin();
if (result == calibrate_return_ok) { if (result == calibrate_return_ok) {
for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) {
if (rgCompassAvailable[cur_mag]) { if (rgCompassAvailable[cur_mag]) {
_emitVehicleTextMessage(QString("[cal] mag #%1 off: x:%2 y:%3 z:%4").arg(cur_mag).arg(-sphere_x[cur_mag]).arg(-sphere_y[cur_mag]).arg(-sphere_z[cur_mag])); _emitVehicleTextMessage(QString("[cal] mag #%1 off: x:%2 y:%3 z:%4").arg(cur_mag).arg(-sphere_x[cur_mag]).arg(-sphere_y[cur_mag]).arg(-sphere_z[cur_mag]));
const char* offsetParam = rgCompassParams[cur_mag][0]; if (cur_mag != 2) {
plugin->getParameterFact(-1, offsetParam)->setRawValue(-sphere_x[cur_mag]); float sensorId;
offsetParam = rgCompassParams[cur_mag][1]; sensorId = cur_mag == 0 ? 2.0f : 5.0f;
plugin->getParameterFact(-1, offsetParam)->setRawValue(-sphere_y[cur_mag]); _vehicle->doCommandLong(0, MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS, sensorId, -sphere_x[cur_mag], -sphere_y[cur_mag], -sphere_z[cur_mag]);
offsetParam = rgCompassParams[cur_mag][2]; }
plugin->getParameterFact(-1, offsetParam)->setRawValue(-sphere_z[cur_mag]);
} }
} }
} }
......
...@@ -1485,12 +1485,31 @@ void Vehicle::emergencyStop(void) ...@@ -1485,12 +1485,31 @@ void Vehicle::emergencyStop(void)
cmd.param7 = 0.0f; cmd.param7 = 0.0f;
cmd.target_system = id(); cmd.target_system = id();
cmd.target_component = 0; cmd.target_component = 0;
mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &cmd); mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &cmd);
sendMessage(msg); sendMessage(msg);
} }
void Vehicle::doCommandLong(int component, MAV_CMD command, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
{
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = command;
cmd.confirmation = 0;
cmd.param1 = param1;
cmd.param2 = param2;
cmd.param3 = param3;
cmd.param4 = param4;
cmd.param5 = param5;
cmd.param6 = param6;
cmd.param7 = param7;
cmd.target_system = id();
cmd.target_component = component;
mavlink_msg_command_long_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &cmd);
sendMessage(msg);
}
const char* VehicleGPSFactGroup::_hdopFactName = "hdop"; const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop"; const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
......
...@@ -504,6 +504,7 @@ public: ...@@ -504,6 +504,7 @@ public:
static const int cMaxRcChannels = 18; static const int cMaxRcChannels = 18;
bool containsLink(LinkInterface* link) { return _links.contains(link); } bool containsLink(LinkInterface* link) { return _links.contains(link); }
void doCommandLong(int component, MAV_CMD command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
public slots: public slots:
void setLatitude(double latitude); void setLatitude(double latitude);
......
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