31 SITL *SITL::_s_instance =
nullptr;
126 void SITL::simstate_send(mavlink_channel_t
chan)
136 mavlink_msg_simstate_send(chan,
146 state.latitude*1.0e7,
147 state.longitude*1.0e7);
168 lat : (int32_t)(
state.latitude*1.0e7),
169 lng : (int32_t)(
state.longitude*1.0e7),
182 void SITL::convert_body_frame(
double rollDeg,
double pitchDeg,
183 double rollRate,
double pitchRate,
double yawRate,
184 double *p,
double *q,
double *r)
186 double phi, theta, phiDot, thetaDot, psiDot;
188 phi =
ToRad(rollDeg);
189 theta =
ToRad(pitchDeg);
190 phiDot =
ToRad(rollRate);
191 thetaDot =
ToRad(pitchRate);
192 psiDot =
ToRad(yawRate);
194 *p = phiDot - psiDot*sin(theta);
195 *q = cos(phi)*thetaDot + sin(phi)*psiDot*cos(theta);
196 *r = cos(phi)*psiDot*cos(theta) - sin(phi)*thetaDot;
212 float phi, theta, psi;
215 float phiDot = p + tanf(theta)*(q*sinf(phi) + r*cosf(phi));
216 float thetaDot = q*cosf(phi) - r*sinf(phi);
217 if (fabsf(cosf(theta)) < 1.0e-20
f) {
220 float psiDot = (q*sinf(phi) + r*cosf(phi))/cosf(theta);
221 return Vector3f(phiDot, thetaDot, psiDot);
void to_euler(float *roll, float *pitch, float *yaw) const
Vector3< float > Vector3f
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
#define AP_GROUPINFO(name, idx, clazz, element, def)
void WriteBlock(const void *pBuffer, uint16_t size)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define AP_SUBGROUPEXTENSION(name, idx, clazz, vinfo)
Common definitions and utility routines for the ArduPilot libraries.
DataFlash_Class DataFlash
static constexpr float radians(float deg)
AP_HAL::AnalogSource * chan
static SITL * get_instance()
#define LOG_PACKET_HEADER_INIT(id)