Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef MRPT_LOCALIZATION_NODE_H
00035 #define MRPT_LOCALIZATION_NODE_H
00036
00037 #include <cstring>
00038
00039 #include <ros/ros.h>
00040 #include <tf/transform_listener.h>
00041 #include <tf/transform_broadcaster.h>
00042 #include <std_msgs/Header.h>
00043 #include <nav_msgs/Odometry.h>
00044 #include <nav_msgs/GetMap.h>
00045 #include <sensor_msgs/LaserScan.h>
00046 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00047 #include <nav_msgs/OccupancyGrid.h>
00048 #include <nav_msgs/MapMetaData.h>
00049 #include <dynamic_reconfigure/server.h>
00050
00051 #include <mrpt/math.h>
00052 #include <mrpt/version.h>
00053 #include <mrpt/obs/CObservationOdometry.h>
00054 using mrpt::obs::CObservationOdometry;
00055
00056 #include "mrpt_localization/MotionConfig.h"
00057 #include "mrpt_localization/mrpt_localization.h"
00058 #include "mrpt_msgs/ObservationRangeBeacon.h"
00059
00061 class PFLocalizationNode : public PFLocalization
00062 {
00063 MRPT_ROS_LOG_MACROS;
00064
00065 public:
00066 struct Parameters : public PFLocalization::Parameters
00067 {
00068 static const int MOTION_MODEL_GAUSSIAN = 0;
00069 static const int MOTION_MODEL_THRUN = 1;
00070 Parameters(PFLocalizationNode* p);
00071 ros::NodeHandle node;
00072 void callbackParameters(
00073 mrpt_localization::MotionConfig& config, uint32_t level);
00074 dynamic_reconfigure::Server<mrpt_localization::MotionConfig>
00075 reconfigure_server_;
00076 dynamic_reconfigure::Server<
00077 mrpt_localization::MotionConfig>::CallbackType reconfigure_cb_;
00078 void update(const unsigned long& loop_count);
00079 double rate;
00080 double transform_tolerance;
00081
00082 double no_update_tolerance;
00083
00084 double no_inputs_tolerance;
00085
00086 int parameter_update_skip;
00087 int particlecloud_update_skip;
00088 int map_update_skip;
00089 std::string tf_prefix;
00090 std::string base_frame_id;
00091 std::string odom_frame_id;
00092 std::string global_frame_id;
00093 bool update_while_stopped;
00094 bool pose_broadcast;
00095 bool tf_broadcast;
00096 bool use_map_topic;
00097 bool first_map_only;
00098 };
00099
00100 PFLocalizationNode(ros::NodeHandle& n);
00101 virtual ~PFLocalizationNode();
00102 void init();
00103 void loop();
00104 void callbackLaser(const sensor_msgs::LaserScan&);
00105 void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon&);
00106 void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped&);
00107 void odometryForCallback(
00108 CObservationOdometry::Ptr&, const std_msgs::Header&);
00109 void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped&);
00110 void callbackOdometry(const nav_msgs::Odometry&);
00111 void callbackMap(const nav_msgs::OccupancyGrid&);
00112 void updateMap(const nav_msgs::OccupancyGrid&);
00113 void publishTF();
00114 void publishPose();
00115
00116 private:
00117 ros::NodeHandle nh_;
00118 bool first_map_received_;
00119 ros::Time time_last_input_;
00120 unsigned long long loop_count_;
00121 nav_msgs::GetMap::Response resp_;
00122 ros::Subscriber sub_init_pose_;
00123 ros::Subscriber sub_odometry_;
00124 std::vector<ros::Subscriber> sub_sensors_;
00125 ros::Subscriber sub_map_;
00126 ros::ServiceClient client_map_;
00127 ros::Publisher pub_particles_;
00128 ros::Publisher pub_map_;
00129 ros::Publisher pub_metadata_;
00130 ros::Publisher pub_pose_;
00131 ros::ServiceServer service_map_;
00132 tf::TransformListener tf_listener_;
00133 tf::TransformBroadcaster tf_broadcaster_;
00134 std::map<std::string, mrpt::poses::CPose3D> laser_poses_;
00135 std::map<std::string, mrpt::poses::CPose3D> beacon_poses_;
00136
00137
00138 Parameters* param();
00139 void update();
00140 void updateSensorPose(std::string frame_id);
00141
00142 void publishParticles();
00143 void useROSLogLevel();
00144
00145 bool waitForTransform(
00146 mrpt::poses::CPose3D& des, const std::string& target_frame,
00147 const std::string& source_frame, const ros::Time& time,
00148 const ros::Duration& timeout,
00149 const ros::Duration& polling_sleep_duration = ros::Duration(0.01));
00150 bool mapCallback(
00151 nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res);
00152 void publishMap();
00153 virtual bool waitForMap();
00154 };
00155
00156 #endif // MRPT_LOCALIZATION_NODE_H