Go to the documentation of this file.
30 #include <hector_pose_estimation/ros/parameters.h>
41 #ifdef USE_HECTOR_TIMING
42 #include <hector_diagnostics/timing.h>
50 , transform_listener_(0)
51 , world_nav_transform_updated_(true)
52 , world_nav_transform_valid_(false)
53 , sensor_pose_roll_(0), sensor_pose_pitch_(0), sensor_pose_yaw_(0)
59 #if defined(USE_HECTOR_UAV_MSGS)
79 ROS_WARN(
"Parameter 'publish_world_map_transform' is deprecated. Use 'publish_world_other_transform' and 'other_frame' instead.");
83 ROS_WARN(
"Parameter 'map_frame' is deprecated. Use 'other_frame' instead.");
94 ROS_ERROR(
"Intitialization of pose estimation failed!");
101 #if defined(USE_HECTOR_UAV_MSGS)
130 #ifdef USE_HECTOR_TIMING
177 tf::Vector3 linear_acceleration_body(imu->linear_acceleration.x, imu->linear_acceleration.y, imu->linear_acceleration.z);
178 linear_acceleration_body.normalize();
179 sensor_pose_roll_ = atan2(linear_acceleration_body.y(), linear_acceleration_body.z());
200 #if defined(USE_HECTOR_UAV_MSGS)
201 void PoseEstimationNode::baroCallback(
const hector_uav_msgs::AltimeterConstPtr& altimeter) {
203 m->add(
Baro::Update(altimeter->pressure, altimeter->qnh));
211 update(0) = height->point.z;
215 sensor_pose_.pose.position.z = height->point.z - m->getElevation();
224 update.x() = magnetic->vector.x;
225 update.y() = magnetic->vector.y;
226 update.z() = magnetic->vector.z;
237 if (gps->status.status == sensor_msgs::NavSatStatus::STATUS_NO_FIX) {
243 update.latitude = gps->latitude * M_PI/180.0;
244 update.longitude = gps->longitude * M_PI/180.0;
245 update.velocity_north = gps_velocity->vector.x;
246 update.velocity_east = -gps_velocity->vector.y;
250 geometry_msgs::PoseStamped gps_pose;
252 gps_pose.header.stamp = gps->header.stamp;
256 gps_pose.pose.position.x = y(0);
257 gps_pose.pose.position.y = y(1);
259 double track = atan2(gps_velocity->vector.y, gps_velocity->vector.x);
260 gps_pose.pose.orientation.w = cos(track/2);
261 gps_pose.pose.orientation.z = sin(track/2);
274 if (pose->pose.covariance[0] > 0)
sensor_pose_.pose.position.x = pose->pose.pose.position.x;
275 if (pose->pose.covariance[7] > 0)
sensor_pose_.pose.position.y = pose->pose.pose.position.y;
276 if (pose->pose.covariance[14] > 0)
sensor_pose_.pose.position.z = pose->pose.pose.position.z;
278 double yaw, pitch, roll;
292 if (syscommand->data ==
"reset") {
293 ROS_INFO(
"Resetting pose_estimation");
300 geographic_msgs::GeoPose geopose;
322 nav_msgs::Odometry state;
328 geometry_msgs::PoseStamped pose_msg;
334 sensor_msgs::Imu imu_msg;
342 geometry_msgs::Vector3Stamped velocity_msg;
348 geographic_msgs::GeoPose geopose_msg;
354 sensor_msgs::NavSatFix global_msg;
360 geometry_msgs::Vector3Stamped euler_msg;
368 geometry_msgs::Vector3Stamped angular_velocity_msg, linear_acceleration_msg;
397 ROS_WARN(
"Could not find a transformation from %s to %s to publish the world transformation", nav_frame.c_str(),
other_frame_.c_str());
410 #ifdef USE_HECTOR_TIMING
void imuCallback(const sensor_msgs::ImuConstPtr &imu)
ros::Publisher angular_velocity_bias_publisher_
bool publish_world_other_transform_
ros::Publisher pose_publisher_
virtual ~PoseEstimationNode()
void globalReferenceUpdated()
message_filters::Subscriber< geometry_msgs::Vector3Stamped > gps_velocity_subscriber_
virtual void getTransforms(std::vector< tf::StampedTransform > &transforms)
virtual bool getWorldToNavTransform(geometry_msgs::TransformStamped &transform)
bool publish_covariances_
void poseupdateCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
virtual void getImuWithBiases(geometry_msgs::Vector3 &linear_acceleration, geometry_msgs::Vector3 &angular_velocity)
bool world_nav_transform_valid_
void gpsCallback(const sensor_msgs::NavSatFixConstPtr &gps, const geometry_msgs::Vector3StampedConstPtr &gps_velocity)
const MeasurementPtr & addMeasurement(ConcreteMeasurementModel *model, const std::string &name)
double sensor_pose_pitch_
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
ros::Publisher global_reference_publisher_
bool getParam(const std::string &key, bool &b) const
ros::Publisher linear_acceleration_bias_publisher_
void initialize(ParameterRegisterFunc func) const
virtual void getOrientation(double &yaw, double &pitch, double &roll)
ros::Subscriber ahrs_subscriber_
virtual ros::NodeHandle & getPrivateNodeHandle()
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
void publishWorldNavTransform(const ros::TimerEvent &=ros::TimerEvent())
PoseEstimation * pose_estimation_
std::string resolve(const std::string &prefix, const std::string &frame_name)
void setOrientation(const Eigen::MatrixBase< Derived > &orientation)
virtual void getState(nav_msgs::Odometry &state, bool with_covariances=true)
virtual void getGlobal(double &latitude, double &longitude, double &altitude)
ros::Publisher velocity_publisher_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
const SystemPtr & addSystem(ConcreteSystemModel *model, const std::string &name="system")
InputPtr addInput(const InputPtr &input, const std::string &name=std::string())
MeasurementPtr getMeasurement(const std::string &name) const
void syscommandCallback(const std_msgs::StringConstPtr &syscommand)
virtual const GlobalReferencePtr & globalReference()
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
ros::Duration publish_world_nav_transform_period_
std::string getPrefixParam(ros::NodeHandle &nh)
bool publish_world_nav_transform_
bool world_nav_transform_updated_
ros::Publisher imu_publisher_
PoseEstimationNode(const SystemPtr &system=SystemPtr(), const StatePtr &state=StatePtr())
ros::Timer publish_world_nav_transform_timer_
tf::TransformListener * getTransformListener()
ros::Publisher euler_publisher_
virtual void getBias(geometry_msgs::Vector3 &angular_velocity, geometry_msgs::Vector3 &linear_acceleration)
ros::Subscriber poseupdate_subscriber_
void setRollPitch(const Quaternion &orientation)
virtual ros::NodeHandle & getNodeHandle()
Model::MeasurementVector MeasurementVector
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf::TransformBroadcaster * getTransformBroadcaster()
ros::Publisher geopose_publisher_
void heightCallback(const geometry_msgs::PointStampedConstPtr &height)
ros::Subscriber magnetic_subscriber_
ros::Publisher timing_publisher_
message_filters::Subscriber< sensor_msgs::NavSatFix > gps_subscriber_
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
void magneticCallback(const geometry_msgs::Vector3StampedConstPtr &magnetic)
ros::Publisher state_publisher_
Connection registerCallback(C &callback)
ros::Publisher gps_pose_publisher_
message_filters::TimeSynchronizer< sensor_msgs::NavSatFix, geometry_msgs::Vector3Stamped > * gps_synchronizer_
virtual void getHeader(std_msgs::Header &header)
ros::Subscriber height_subscriber_
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
InputPtr setInput(const Input &input, std::string name=std::string())
T & getAs(const std::string &key) const
ros::Subscriber rollpitch_subscriber_
void twistupdateCallback(const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
traits::Update< BaroModel >::type Update
tf::TransformBroadcaster transform_broadcaster_
void ahrsCallback(const sensor_msgs::ImuConstPtr &ahrs)
virtual void updateWorldToOtherTransform(tf::StampedTransform &world_to_other_transform)
virtual ParameterList & parameters()
void rollpitchCallback(const sensor_msgs::ImuConstPtr &attitude)
uint32_t getNumSubscribers() const
Eigen::Quaternion< ScalarType > Quaternion
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Subscriber imu_subscriber_
virtual void getPose(geometry_msgs::Pose &pose)
ros::Publisher sensor_pose_publisher_
virtual void getVelocity(geometry_msgs::Vector3 &vector)
ros::Publisher global_fix_publisher_
ros::Subscriber twistupdate_subscriber_
ros::Subscriber syscommand_subscriber_
std::vector< tf::StampedTransform > transforms_
tf::TransformListener * transform_listener_
geometry_msgs::PoseStamped sensor_pose_
geometry_msgs::TransformStamped world_nav_transform_