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 #pragma once
35 
36 #include <dynamic_reconfigure/server.h>
37 #include <geometry_msgs/PoseWithCovarianceStamped.h>
38 #include <mrpt/obs/CObservationOdometry.h>
39 #include <nav_msgs/GetMap.h>
40 #include <nav_msgs/MapMetaData.h>
41 #include <nav_msgs/OccupancyGrid.h>
42 #include <nav_msgs/Odometry.h>
43 #include <ros/ros.h>
44 #include <sensor_msgs/LaserScan.h>
45 #include <std_msgs/Header.h>
46 
47 #include <cstring> // size_t
48 
49 #include "geometry_msgs/TransformStamped.h"
50 #include "mrpt_localization/MotionConfig.h"
52 #include "mrpt_msgs/ObservationRangeBeacon.h"
54 #include "tf2_ros/buffer.h"
57 
58 using mrpt::obs::CObservationOdometry;
59 
62 {
63  public:
65  {
66  static const int MOTION_MODEL_GAUSSIAN = 0;
67  static const int MOTION_MODEL_THRUN = 1;
70  void callbackParameters(
71  mrpt_localization::MotionConfig& config, uint32_t level);
72  dynamic_reconfigure::Server<mrpt_localization::MotionConfig>
74  dynamic_reconfigure::Server<
75  mrpt_localization::MotionConfig>::CallbackType reconfigure_cb_;
76  void update(const unsigned long& loop_count);
77  double rate;
79  double no_update_tolerance;
81  double no_inputs_tolerance;
87  std::string base_frame_id;
88  std::string odom_frame_id;
89  std::string global_frame_id;
96  double init_x; // m
97  double init_y; // m
98  double init_phi; //radians
99  double init_std_xy = 0.20; // m
100  double init_std_phi = 0.10; // rad
101  };
102 
104  virtual ~PFLocalizationNode();
105  void init();
106  void loop();
107  void callbackLaser(const sensor_msgs::LaserScan&);
108  void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon&);
109  void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped&);
110  void odometryForCallback(
111  CObservationOdometry::Ptr&, const std_msgs::Header&);
112  void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped&);
113  void callbackOdometry(const nav_msgs::Odometry&);
114  void callbackMap(const nav_msgs::OccupancyGrid&);
115  void updateMap(const nav_msgs::OccupancyGrid&);
116  void publishTF();
117  void publishPose();
118 
119  private:
123  unsigned long long loop_count_;
124  nav_msgs::GetMap::Response resp_;
127  std::vector<ros::Subscriber> sub_sensors_;
135 
138 
140 
141  std::map<std::string, mrpt::poses::CPose3D> laser_poses_;
142  std::map<std::string, mrpt::poses::CPose3D> beacon_poses_;
143 
144  // methods
145  Parameters* param();
146  void update();
147  void updateSensorPose(std::string frame_id);
148 
149  void publishParticles();
150  void useROSLogLevel();
151 
152  bool waitForTransform(
153  mrpt::poses::CPose3D& des, const std::string& target_frame,
154  const std::string& source_frame, const ros::Time& time,
155  const ros::Duration& timeout,
156  const ros::Duration& polling_sleep_duration = ros::Duration(0.01));
157  bool mapCallback(
158  nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res);
159  void publishMap();
160  virtual bool waitForMap();
161 };
tf2_ros::TransformListener tf_listener_
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.
tf2_ros::TransformBroadcaster tf_broadcaster_
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 &)
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)
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 1 2023 03:07:06