36 #include <sensor_msgs/Imu.h> 37 #include <geometry_msgs/Twist.h> 38 #include <nav_msgs/Odometry.h> 39 #include <geometry_msgs/Vector3Stamped.h> 58 bool abslt(
const double& val1,
const double& val2){
59 return std::abs(val1) < val2;
63 return alpha * meas + (1.0 - alpha) * avg;
97 sensor_msgs::ImuPtr imu(
new sensor_msgs::Imu(*msg));
103 imu->angular_velocity.x = 0.0;
104 imu->angular_velocity.y = 0.0;
105 imu->angular_velocity.z = 0.0;
116 geometry_msgs::Vector3StampedPtr bias(
new geometry_msgs::Vector3Stamped());
117 bias->header = imu->header;
123 int main(
int argc,
char **argv){
124 ros::init(argc, argv,
"imu_bias_remover");
153 pub_ = n.
advertise<sensor_msgs::Imu>(
"imu_biased", 10);
154 bias_pub_ = n.
advertise<geometry_msgs::Vector3Stamped>(
"bias", 10);
void publish(const boost::shared_ptr< M > &message) const
geometry_msgs::Vector3 angular_velocity_accumulator
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double accumulator_alpha_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void imu_callback(const sensor_msgs::ImuConstPtr &msg)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void cmd_vel_callback(const geometry_msgs::TwistConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void odom_callback(const nav_msgs::OdometryConstPtr &msg)
bool abslt(const double &val1, const double &val2)
double accumulator_update(const double &alpha, const double &avg, const double &meas)
double cmd_vel_threshold_