46 static const double EPS = 1e-5;
54 OdomEstimationNode::OdomEstimationNode()
55 : odom_active_(false),
59 odom_initializing_(false),
60 imu_initializing_(false),
61 vo_initializing_(false),
62 gps_initializing_(false),
67 odom_callback_counter_(0),
68 imu_callback_counter_(0),
69 vo_callback_counter_(0),
70 gps_callback_counter_(0),
87 nh_private.
param(
"freq", freq, 30.0);
104 pose_pub_ = nh_private.
advertise<geometry_msgs::PoseWithCovarianceStamped>(
"odom_combined", 10);
114 else ROS_DEBUG(
"Odom sensor will NOT be used");
121 else ROS_DEBUG(
"Imu sensor will NOT be used");
128 else ROS_DEBUG(
"VO sensor will NOT be used");
134 else ROS_DEBUG(
"GPS sensor will NOT be used");
186 for (
unsigned int i=0; i<6; i++)
187 for (
unsigned int j=0; j<6; j++)
197 ROS_INFO(
"Initializing Odom sensor");
204 else ROS_DEBUG(
"Waiting to activate Odom, because Odom measurements are still %f sec in the future.",
229 quaternionMsgToTF(imu->orientation, orientation);
231 for (
unsigned int i=0; i<3; i++)
232 for (
unsigned int j=0; j<3; j++)
241 ROS_WARN(
"Could not transform imu message from %s to %s. Imu will not be activated yet.", imu->header.frame_id.c_str(),
base_footprint_frame_.c_str());
243 ROS_DEBUG(
"Could not transform imu message from %s to %s. Imu will not be activated yet.", imu->header.frame_id.c_str(),
base_footprint_frame_.c_str());
254 SymmetricMatrix measNoiseImu_Cov(3); measNoiseImu_Cov = 0;
255 measNoiseImu_Cov(1,1) = pow(0.00017,2);
256 measNoiseImu_Cov(2,2) = pow(0.00017,2);
257 measNoiseImu_Cov(3,3) = pow(0.00017,2);
268 ROS_INFO(
"Initializing Imu sensor");
275 else ROS_DEBUG(
"Waiting to activate IMU, because IMU measurements are still %f sec in the future.",
300 poseMsgToTF(vo->pose.pose,
vo_meas_);
301 for (
unsigned int i=0; i<6; i++)
302 for (
unsigned int j=0; j<6; j++)
318 else ROS_DEBUG(
"Waiting to activate VO, because VO measurements are still %f sec in the future.",
327 << Rx <<
" " << Ry <<
" " << Rz << endl;
342 for (
unsigned int i=0; i<3; i++)
343 for (
unsigned int j=0; j<3; j++)
352 ROS_INFO(
"Initializing GPS sensor");
359 else ROS_DEBUG(
"Waiting to activate GPS, because GPS measurements are still %f sec in the future.",
379 if (diff > 1.0)
ROS_ERROR(
"Timestamps of odometry and imu are %f seconds apart.", diff);
389 ROS_INFO(
"Odom sensor not active any more");
394 ROS_INFO(
"Imu sensor not active any more");
399 ROS_INFO(
"VO sensor not active any more");
405 ROS_INFO(
"GPS sensor not active any more");
421 bool diagnostics =
true;
438 ColumnVector estimate;
442 for (
unsigned int i=1; i<=6; i++)
448 ROS_WARN(
"Robot pose ekf diagnostics discovered a potential problem");
458 ROS_INFO(
"Kalman filter initialized with gps and imu measurement");
465 ROS_INFO(
"Kalman filter initialized with gps and odometry measurement");
472 ROS_INFO(
"Kalman filter initialized with gps and visual odometry measurement");
476 ROS_INFO(
"Kalman filter initialized with odom measurement");
480 ROS_INFO(
"Kalman filter initialized with vo measurement");
489 ss <<
"Input:" << endl;
490 ss <<
" * Odometry sensor" << endl;
491 ss <<
" - is ";
if (!
odom_used_) ss <<
"NOT "; ss <<
"used" << endl;
492 ss <<
" - is ";
if (!
odom_active_) ss <<
"NOT "; ss <<
"active" << endl;
495 ss <<
" * IMU sensor" << endl;
496 ss <<
" - is ";
if (!
imu_used_) ss <<
"NOT "; ss <<
"used" << endl;
497 ss <<
" - is ";
if (!
imu_active_) ss <<
"NOT "; ss <<
"active" << endl;
500 ss <<
" * Visual Odometry sensor" << endl;
501 ss <<
" - is ";
if (!
vo_used_) ss <<
"NOT "; ss <<
"used" << endl;
502 ss <<
" - is ";
if (!
vo_active_) ss <<
"NOT "; ss <<
"active" << endl;
505 ss <<
" * GPS sensor" << endl;
506 ss <<
" - is ";
if (!
gps_used_) ss <<
"NOT "; ss <<
"used" << endl;
507 ss <<
" - is ";
if (!
gps_active_) ss <<
"NOT "; ss <<
"active" << endl;
510 ss <<
"Output:" << endl;
511 ss <<
" * Robot pose ekf filter" << endl;
515 resp.status = ss.str();
530 int main(
int argc,
char **argv)
void spin(const ros::TimerEvent &e)
the mail filter loop that will be called periodically
OdomEstimation my_filter_
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
virtual ~OdomEstimationNode()
destructor
unsigned int vo_callback_counter_
MatrixWrapper::SymmetricMatrix odom_covariance_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
unsigned int imu_callback_counter_
std::string base_footprint_frame_
bool getStatus(robot_pose_ekf::GetStatus::Request &req, robot_pose_ekf::GetStatus::Response &resp)
get the status of the filter
void initialize(const tf::Transform &prior, const ros::Time &time)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
geometry_msgs::PoseWithCovarianceStamped output_
ros::Time odom_init_stamp_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void odomCallback(const OdomConstPtr &odom)
callback function for odo data
MatrixWrapper::SymmetricMatrix vo_covariance_
tf::TransformBroadcaster odom_broadcaster_
void voCallback(const VoConstPtr &vo)
callback function for vo data
ROSCPP_DECL void spin(Spinner &spinner)
std::string resolve(const std::string &prefix, const std::string &frame_name)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void imuCallback(const ImuConstPtr &imu)
callback function for imu data
TFSIMD_FORCE_INLINE const tfScalar & z() const
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
MatrixWrapper::SymmetricMatrix imu_covariance_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string getTopic() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
bool update(bool odom_active, bool imu_active, bool gps_active, bool vo_active, const ros::Time &filter_time, bool &diagnostics_res)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Time gps_init_stamp_
void addMeasurement(const tf::StampedTransform &meas)
unsigned int ekf_sent_counter_
ros::Subscriber odom_sub_
#define ROS_INFO_STREAM(args)
tf::TransformListener robot_state_
unsigned int gps_callback_counter_
void setBaseFootprintFrame(const std::string &base_frame)
ros::ServiceServer state_srv_
std::string getTopic() const
ros::Time imu_init_stamp_
MatrixWrapper::SymmetricMatrix gps_covariance_
void gpsCallback(const GpsConstPtr &gps)
callback function for vo data
void setOutputFrame(const std::string &output_frame)
std::string output_frame_
void getEstimate(MatrixWrapper::ColumnVector &estimate)
unsigned int odom_callback_counter_
int main(int argc, char **argv)