IMU输出的数据中的线速度和线加速度,是在世界坐标系下,即NED北-东-下坐标系。
AirSim中,IMU的读数输出对应两个坐标系:
AirSim通过程序来生成IMU数据,原理是获取vehicle状态和环境重力状态来计算,代码为:IMU数据生成程序。
void updateOutput()
{
Output output; //IMU生成的数据
// 第一步:获得vehicle的真值数据
const GroundTruth& ground_truth = getGroundTruth(); //得到无人机真值,包括*.kinematics动力学数据
// 第二步:获得角速度
output.angular_velocity = ground_truth.kinematics->twist.angular;//将无人机的角速度赋值给output.angular_velocity,FLU坐标系下
// 第三步:获得加速度
output.linear_acceleration = ground_truth.kinematics->accelerations.linear - ground_truth.environment->getState().gravity;//生成IMU加速度数据(世界坐标系NED),IMU加速度不含重力加速度
// 第四步:获得位姿
output.orientation = ground_truth.kinematics->pose.orientation;// 得到无人机在世界系下的姿态
// 第五步:坐标转换??
//acceleration is in world frame so transform to body frame
output.linear_acceleration = VectorMath::transformToBodyFrame(output.linear_acceleration,
ground_truth.kinematics->pose.orientation, true);// 将加速度转换为体坐标系下,这里使用表明Rwb后直接作为IMU数据,而没有Rbi,表明imu系与body系为同一系
// 第六步:add noise
addNoise(output.linear_acceleration, output.angular_velocity);
// TODO: Add noise in orientation?
// 第七步:增加时间戳
output.time_stamp = clock()->nowNanos(); // 真实cpu时间??
setOutput(output);
关于坐标变换函数的代码,在AirSim/AirLib/include/common/VectorMath.hpp中展示的代码如下:
static Vector3T transformToBodyFrame(const Vector3T& v_world, const QuaternionT& q_world, bool assume_unit_quat = true)
{
return rotateVectorReverse(v_world, q_world, assume_unit_quat);
}
static Vector3T transformToBodyFrame(const Vector3T& v_world, const Pose& body_world, bool assume_unit_quat = true)
{
//translate
Vector3T translated = v_world - body_world.position;
//rotate
return transformToBodyFrame(translated, body_world.orientation, assume_unit_quat);
}
static Pose transformToBodyFrame(const Pose& pose_world, const Pose& body_world, bool assume_unit_quat = true)
{
//translate
Vector3T translated = pose_world.position - body_world.position;
//rotate vector
Vector3T v_body = transformToBodyFrame(translated, body_world.orientation, assume_unit_quat);
//rotate orientation
QuaternionT q_body = rotateQuaternionReverse(pose_world.orientation, body_world.orientation, assume_unit_quat);
return Pose(v_body, q_body);
}
源自: Sensor APIs: IMU
可以跳转到hello_drone.py或hello_drone.cpp参考demo代码。
或者查看下面的完整API函数:
读取IMU数据函数原型:
msr::airlib::ImuBase::Output getImuData(const std::string& imu_name = "", const std::string& vehicle_name = "");
读取IMU数据的函数:
// IMU API: AirSim/AirLib/include/api/VehicleApiBase.hpp
virtual const ImuBase::Output& getImuData(const std::string& imu_name) const
{
auto* imu = static_cast<const ImuBase*>(findSensorByName(imu_name, SensorBase::SensorType::Imu));
if (imu == nullptr)
throw VehicleControllerException(Utils::stringf("No IMU with name %s exist on vehicle", imu_name.c_str()));
return imu->getOutput();
}
读取IMU数据调用:
imu_data = client.getImuData(imu_name = "", vehicle_name = "")
相关数据源码:Output
//源码:AirSim/AirLib/include/sensors/imu/ImuBase.hpp
class ImuBase : public SensorBase
{
...
public: //types
struct Output
{ //structure is same as ROS IMU message 与ROS IMU message一致
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
TTimePoint time_stamp;
Quaternionr orientation;
Vector3r angular_velocity;
Vector3r linear_acceleration;
};
...