mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter HIL: changed calls to setHIL to send in time as a uint32_t (it was a float)
This commit is contained in:
parent
91cde15c27
commit
c034e38cbd
@ -1877,7 +1877,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
mavlink_msg_gps_raw_decode(msg, &packet);
|
mavlink_msg_gps_raw_decode(msg, &packet);
|
||||||
|
|
||||||
// set gps hil sensor
|
// set gps hil sensor
|
||||||
g_gps->setHIL(packet.usec/1000.0,packet.lat,packet.lon,packet.alt,
|
g_gps->setHIL(packet.usec/1000,packet.lat,packet.lon,packet.alt,
|
||||||
packet.v,packet.hdg,0,0);
|
packet.v,packet.hdg,0,0);
|
||||||
if (gps_base_alt == 0) {
|
if (gps_base_alt == 0) {
|
||||||
gps_base_alt = packet.alt*100;
|
gps_base_alt = packet.alt*100;
|
||||||
@ -1944,7 +1944,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
float cog = wrap_360(ToDeg(atan2(packet.vx, packet.vy)) * 100);
|
float cog = wrap_360(ToDeg(atan2(packet.vx, packet.vy)) * 100);
|
||||||
|
|
||||||
// set gps hil sensor
|
// set gps hil sensor
|
||||||
g_gps->setHIL(packet.time_usec/1000.0,
|
g_gps->setHIL(packet.time_usec/1000,
|
||||||
packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3,
|
packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3,
|
||||||
vel*1.0e-2, cog*1.0e-2, 0, 10);
|
vel*1.0e-2, cog*1.0e-2, 0, 10);
|
||||||
|
|
||||||
@ -2006,7 +2006,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
mavlink_msg_gps_raw_decode(msg, &packet);
|
mavlink_msg_gps_raw_decode(msg, &packet);
|
||||||
|
|
||||||
// set gps hil sensor
|
// set gps hil sensor
|
||||||
g_gps->setHIL(packet.usec/1000.0,packet.lat,packet.lon,packet.alt,
|
g_gps->setHIL(packet.usec/1000,packet.lat,packet.lon,packet.alt,
|
||||||
packet.v,packet.hdg,0,0);
|
packet.v,packet.hdg,0,0);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -38,7 +38,7 @@ bool AP_GPS_HIL::read(void)
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_GPS_HIL::setHIL(long _time, float _latitude, float _longitude, float _altitude,
|
void AP_GPS_HIL::setHIL(uint32_t _time, float _latitude, float _longitude, float _altitude,
|
||||||
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
|
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
|
||||||
{
|
{
|
||||||
time = _time;
|
time = _time;
|
||||||
|
@ -30,7 +30,7 @@ public:
|
|||||||
* @param speed_3d - ground speed in meters/second
|
* @param speed_3d - ground speed in meters/second
|
||||||
* @param altitude - altitude in meters
|
* @param altitude - altitude in meters
|
||||||
*/
|
*/
|
||||||
virtual void setHIL(long time, float latitude, float longitude, float altitude,
|
virtual void setHIL(uint32_t time, float latitude, float longitude, float altitude,
|
||||||
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -70,7 +70,7 @@ GPS::update(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
GPS::setHIL(long _time, float _latitude, float _longitude, float _altitude,
|
GPS::setHIL(uint32_t _time, float _latitude, float _longitude, float _altitude,
|
||||||
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
|
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
@ -112,7 +112,7 @@ public:
|
|||||||
bool print_errors; ///< deprecated
|
bool print_errors; ///< deprecated
|
||||||
|
|
||||||
// HIL support
|
// HIL support
|
||||||
virtual void setHIL(long time, float latitude, float longitude, float altitude,
|
virtual void setHIL(uint32_t time, float latitude, float longitude, float altitude,
|
||||||
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
||||||
|
|
||||||
/// Time in milliseconds after which we will assume the GPS is no longer
|
/// Time in milliseconds after which we will assume the GPS is no longer
|
||||||
|
Loading…
Reference in New Issue
Block a user