mrpt_localization_node.h
Go to the documentation of this file.
1 /***********************************************************************************
2  * Revised BSD License *
3  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
4  * All rights reserved. *
5  * *
6  * Redistribution and use in source and binary forms, with or without *
7  * modification, are permitted provided that the following conditions are met: *
8  * * Redistributions of source code must retain the above copyright *
9  * notice, this list of conditions and the following disclaimer. *
10  * * Redistributions in binary form must reproduce the above copyright *
11  * notice, this list of conditions and the following disclaimer in the *
12  * documentation and/or other materials provided with the distribution. *
13  * * Neither the name of the Vienna University of Technology nor the *
14  * names of its contributors may be used to endorse or promote products *
15  * derived from this software without specific prior written permission. *
16  * *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  *AND *
19  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20  **
21  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
22  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
23  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
24  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  **
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
27  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
28  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
29  **
30  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  ** *
32  ***********************************************************************************/
33 
34 #ifndef MRPT_LOCALIZATION_NODE_H
35 #define MRPT_LOCALIZATION_NODE_H
36 
37 #include <cstring> // size_t
38 
39 #include <ros/ros.h>
40 #include <tf/transform_listener.h>
42 #include <std_msgs/Header.h>
43 #include <nav_msgs/Odometry.h>
44 #include <nav_msgs/GetMap.h>
45 #include <sensor_msgs/LaserScan.h>
46 #include <geometry_msgs/PoseWithCovarianceStamped.h>
47 #include <nav_msgs/OccupancyGrid.h>
48 #include <nav_msgs/MapMetaData.h>
49 #include <dynamic_reconfigure/server.h>
50 
51 #include <mrpt/version.h>
52 #include <mrpt/obs/CObservationOdometry.h>
53 using mrpt::obs::CObservationOdometry;
54 
55 #include "mrpt_localization/MotionConfig.h"
57 #include "mrpt_msgs/ObservationRangeBeacon.h"
58 
61 {
63 
64  public:
66  {
67  static const int MOTION_MODEL_GAUSSIAN = 0;
68  static const int MOTION_MODEL_THRUN = 1;
71  void callbackParameters(
72  mrpt_localization::MotionConfig& config, uint32_t level);
73  dynamic_reconfigure::Server<mrpt_localization::MotionConfig>
75  dynamic_reconfigure::Server<
76  mrpt_localization::MotionConfig>::CallbackType reconfigure_cb_;
77  void update(const unsigned long& loop_count);
78  double rate;
80  double no_update_tolerance;
82  double no_inputs_tolerance;
88  std::string tf_prefix;
89  std::string base_frame_id;
90  std::string odom_frame_id;
91  std::string global_frame_id;
97  };
98 
100  virtual ~PFLocalizationNode();
101  void init();
102  void loop();
103  void callbackLaser(const sensor_msgs::LaserScan&);
104  void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon&);
105  void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped&);
106  void odometryForCallback(
107  CObservationOdometry::Ptr&, const std_msgs::Header&);
108  void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped&);
109  void callbackOdometry(const nav_msgs::Odometry&);
110  void callbackMap(const nav_msgs::OccupancyGrid&);
111  void updateMap(const nav_msgs::OccupancyGrid&);
112  void publishTF();
113  void publishPose();
114 
115  private:
119  unsigned long long loop_count_;
120  nav_msgs::GetMap::Response resp_;
123  std::vector<ros::Subscriber> sub_sensors_;
133  std::map<std::string, mrpt::poses::CPose3D> laser_poses_;
134  std::map<std::string, mrpt::poses::CPose3D> beacon_poses_;
135 
136  // methods
137  Parameters* param();
138  void update();
139  void updateSensorPose(std::string frame_id);
140 
141  void publishParticles();
142  void useROSLogLevel();
143 
144  bool waitForTransform(
145  mrpt::poses::CPose3D& des, const std::string& target_frame,
146  const std::string& source_frame, const ros::Time& time,
147  const ros::Duration& timeout,
148  const ros::Duration& polling_sleep_duration = ros::Duration(0.01));
149  bool mapCallback(
150  nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res);
151  void publishMap();
152  virtual bool waitForMap();
153 };
154 
155 #endif // MRPT_LOCALIZATION_NODE_H
void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped &)
ros::ServiceClient client_map_
void publishTF()
Publish map -> odom tf; as the filter provides map -> base, we multiply it by base -> odom...
dynamic_reconfigure::Server< mrpt_localization::MotionConfig > reconfigure_server_
ros::Subscriber sub_init_pose_
int parameter_update_skip
we wait before start complaining
void publishPose()
Publish the current pose of the robot.
void updateSensorPose(std::string frame_id)
dynamic_reconfigure::Server< mrpt_localization::MotionConfig >::CallbackType reconfigure_cb_
std::map< std::string, mrpt::poses::CPose3D > beacon_poses_
void callbackParameters(mrpt_localization::MotionConfig &config, uint32_t level)
void odometryForCallback(CObservationOdometry::Ptr &, const std_msgs::Header &)
void callbackOdometry(const nav_msgs::Odometry &)
tf::TransformListener tf_listener_
bool waitForTransform(mrpt::poses::CPose3D &des, const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01))
std::vector< ros::Subscriber > sub_sensors_
ros::Subscriber sub_odometry_
PFLocalizationNode(ros::NodeHandle &n)
void callbackLaser(const sensor_msgs::LaserScan &)
void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon &)
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
tf::TransformBroadcaster tf_broadcaster_
unsigned long long loop_count_
nav_msgs::GetMap::Response resp_
void update(const unsigned long &loop_count)
double no_inputs_tolerance
using filter time instead of Time::now
ros::ServiceServer service_map_
std::map< std::string, mrpt::poses::CPose3D > laser_poses_
void updateMap(const nav_msgs::OccupancyGrid &)
void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped &)
void callbackMap(const nav_msgs::OccupancyGrid &)
double no_update_tolerance
the published tf to extend its validity


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Thu Jun 6 2019 19:44:49