36 #include <sensor_msgs/Imu.h> 44 double dt = msg->header.stamp.toSec() -
imu_->header.stamp.toSec();
45 if(
imu_->header.stamp.sec == 0){
51 imu_->header = msg->header;
52 imu_->angular_velocity = msg->angular_velocity;
53 imu_->angular_velocity_covariance = msg->angular_velocity_covariance;
54 imu_->linear_acceleration = msg->linear_acceleration;
55 imu_->linear_acceleration_covariance = msg->linear_acceleration_covariance;
57 double diff = pow(
imu_->orientation.w, 2.0)-pow(
imu_->orientation.z, 2.0);
58 double mult = 2.0*
imu_->orientation.w*
imu_->orientation.z;
59 double theta = atan2(mult, diff);
61 theta = theta +
imu_->angular_velocity.z*dt;
65 imu_->orientation.z = sin(theta/2.0);
66 imu_->orientation.w = cos(theta/2.0);
73 int main(
int argc,
char **argv){
81 imu_.reset(
new sensor_msgs::Imu());
82 imu_->orientation.w = 1.0;
85 pub_ = n.
advertise<sensor_msgs::Imu>(
"imu_integrated", 10);
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void imu_callback(const sensor_msgs::ImuConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double min_angular_velocity_