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 };
PFLocalizationNode::Parameters::reconfigure_cb_
dynamic_reconfigure::Server< mrpt_localization::MotionConfig >::CallbackType reconfigure_cb_
Definition: mrpt_localization_node.h:75
PFLocalizationNode::callbackLaser
void callbackLaser(const sensor_msgs::LaserScan &)
Definition: mrpt_localization_node.cpp:194
PFLocalizationNode::Parameters::reconfigure_server_
dynamic_reconfigure::Server< mrpt_localization::MotionConfig > reconfigure_server_
Definition: mrpt_localization_node.h:73
PFLocalizationNode::callbackInitialpose
void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped &)
Definition: mrpt_localization_node.cpp:469
PFLocalizationNode::Parameters::update_while_stopped
bool update_while_stopped
Definition: mrpt_localization_node.h:90
PFLocalizationNode
ROS Node.
Definition: mrpt_localization_node.h:61
PFLocalizationNode::Parameters::init_x
double init_x
Definition: mrpt_localization_node.h:96
PFLocalizationNode::Parameters::particlecloud_update_skip
int particlecloud_update_skip
Definition: mrpt_localization_node.h:85
PFLocalizationNode::mapCallback
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: mrpt_localization_node.cpp:514
ros::Publisher
PFLocalizationNode::Parameters::global_frame_id
std::string global_frame_id
Definition: mrpt_localization_node.h:89
PFLocalizationNode::publishPose
void publishPose()
Publish the current pose of the robot.
Definition: mrpt_localization_node.cpp:660
PFLocalizationNode::publishTF
void publishTF()
Publish map -> odom tf; as the filter provides map -> base, we multiply it by base -> odom.
Definition: mrpt_localization_node.cpp:560
PFLocalizationNode::Parameters::base_frame_id
std::string base_frame_id
Definition: mrpt_localization_node.h:87
PFLocalizationNode::waitForTransform
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))
Definition: mrpt_localization_node.cpp:169
ros.h
PFLocalizationNode::first_map_received_
bool first_map_received_
Definition: mrpt_localization_node.h:121
PFLocalizationNode::publishMap
void publishMap()
Definition: mrpt_localization_node.cpp:522
PFLocalizationNode::sub_map_
ros::Subscriber sub_map_
Definition: mrpt_localization_node.h:128
PFLocalizationNode::Parameters::first_map_only
bool first_map_only
Definition: mrpt_localization_node.h:95
PFLocalizationNode::odometryForCallback
void odometryForCallback(CObservationOdometry::Ptr &, const std_msgs::Header &)
Definition: mrpt_localization_node.cpp:345
mrpt_localization.h
buffer.h
PFLocalizationNode::pub_metadata_
ros::Publisher pub_metadata_
Definition: mrpt_localization_node.h:132
PFLocalizationNode::Parameters::update
void update(const unsigned long &loop_count)
Definition: mrpt_localization_node_parameters.cpp:95
PFLocalizationNode::callbackRobotPose
void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped &)
Definition: mrpt_localization_node.cpp:272
PFLocalizationNode::sub_odometry_
ros::Subscriber sub_odometry_
Definition: mrpt_localization_node.h:126
PFLocalizationNode::Parameters::init_phi
double init_phi
Definition: mrpt_localization_node.h:98
PFLocalizationNode::Parameters::init_std_xy
double init_std_xy
Definition: mrpt_localization_node.h:99
transform_broadcaster.h
PFLocalizationNode::callbackBeacon
void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon &)
Definition: mrpt_localization_node.cpp:233
PFLocalization
Definition: mrpt_localization.h:45
PFLocalizationNode::laser_poses_
std::map< std::string, mrpt::poses::CPose3D > laser_poses_
Definition: mrpt_localization_node.h:141
PFLocalizationNode::param
Parameters * param()
Definition: mrpt_localization_node.cpp:74
ros::ServiceServer
PFLocalizationNode::sub_init_pose_
ros::Subscriber sub_init_pose_
Definition: mrpt_localization_node.h:125
PFLocalization::Parameters
Definition: mrpt_localization.h:79
tf2_ros::TransformListener
PFLocalizationNode::callbackMap
void callbackMap(const nav_msgs::OccupancyGrid &)
Definition: mrpt_localization_node.cpp:411
PFLocalizationNode::client_map_
ros::ServiceClient client_map_
Definition: mrpt_localization_node.h:129
PFLocalizationNode::callbackOdometry
void callbackOdometry(const nav_msgs::Odometry &)
Definition: mrpt_localization_node.cpp:482
PFLocalizationNode::Parameters::MOTION_MODEL_GAUSSIAN
static const int MOTION_MODEL_GAUSSIAN
Definition: mrpt_localization_node.h:66
PFLocalizationNode::PFLocalizationNode
PFLocalizationNode(ros::NodeHandle &n)
Definition: mrpt_localization_node.cpp:66
PFLocalizationNode::~PFLocalizationNode
virtual ~PFLocalizationNode()
Definition: mrpt_localization_node.cpp:65
PFLocalizationNode::Parameters::MOTION_MODEL_THRUN
static const int MOTION_MODEL_THRUN
Definition: mrpt_localization_node.h:67
PFLocalizationNode::waitForMap
virtual bool waitForMap()
Definition: mrpt_localization_node.cpp:365
PFLocalizationNode::pub_map_
ros::Publisher pub_map_
Definition: mrpt_localization_node.h:131
PFLocalizationNode::Parameters::parameter_update_skip
int parameter_update_skip
we wait before start complaining
Definition: mrpt_localization_node.h:84
PFLocalizationNode::update
void update()
PFLocalizationNode::beacon_poses_
std::map< std::string, mrpt::poses::CPose3D > beacon_poses_
Definition: mrpt_localization_node.h:142
PFLocalizationNode::tf_listener_
tf2_ros::TransformListener tf_listener_
Definition: mrpt_localization_node.h:137
ros::ServiceClient
tf2_ros::Buffer
PFLocalizationNode::Parameters
Definition: mrpt_localization_node.h:64
PFLocalizationNode::Parameters::map_update_skip
int map_update_skip
Definition: mrpt_localization_node.h:86
PFLocalizationNode::Parameters::rate
double rate
Definition: mrpt_localization_node.h:77
PFLocalizationNode::sub_sensors_
std::vector< ros::Subscriber > sub_sensors_
Definition: mrpt_localization_node.h:127
PFLocalizationNode::service_map_
ros::ServiceServer service_map_
Definition: mrpt_localization_node.h:134
PFLocalizationNode::init
void init()
Definition: mrpt_localization_node.cpp:79
PFLocalizationNode::nh_
ros::NodeHandle nh_
Definition: mrpt_localization_node.h:120
PFLocalizationNode::updateMap
void updateMap(const nav_msgs::OccupancyGrid &)
Definition: mrpt_localization_node.cpp:507
PFLocalizationNode::Parameters::callbackParameters
void callbackParameters(mrpt_localization::MotionConfig &config, uint32_t level)
Definition: mrpt_localization_node_parameters.cpp:119
PFLocalizationNode::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: mrpt_localization_node.h:136
transform_listener.h
PFLocalizationNode::loop_count_
unsigned long long loop_count_
Definition: mrpt_localization_node.h:123
PFLocalizationNode::time_last_input_
ros::Time time_last_input_
Definition: mrpt_localization_node.h:122
ros::Time
PFLocalizationNode::loop
void loop()
Definition: mrpt_localization_node.cpp:149
PFLocalizationNode::Parameters::transform_tolerance
double transform_tolerance
Definition: mrpt_localization_node.h:78
PFLocalizationNode::Parameters::no_inputs_tolerance
double no_inputs_tolerance
using filter time instead of Time::now
Definition: mrpt_localization_node.h:82
PFLocalizationNode::Parameters::tf_broadcast
bool tf_broadcast
Definition: mrpt_localization_node.h:93
PFLocalizationNode::Parameters::init_std_phi
double init_std_phi
Definition: mrpt_localization_node.h:100
PFLocalizationNode::Parameters::init_y
double init_y
Definition: mrpt_localization_node.h:97
PFLocalizationNode::Parameters::pose_broadcast
bool pose_broadcast
Definition: mrpt_localization_node.h:92
tf2_ros::TransformBroadcaster
PFLocalizationNode::Parameters::no_update_tolerance
double no_update_tolerance
the published tf to extend its validity
Definition: mrpt_localization_node.h:80
tf2_geometry_msgs.h
PFLocalizationNode::pub_particles_
ros::Publisher pub_particles_
Definition: mrpt_localization_node.h:130
PFLocalizationNode::updateSensorPose
void updateSensorPose(std::string frame_id)
Definition: mrpt_localization_node.cpp:424
PFLocalizationNode::Parameters::odom_frame_id
std::string odom_frame_id
Definition: mrpt_localization_node.h:88
PFLocalizationNode::publishParticles
void publishParticles()
Definition: mrpt_localization_node.cpp:537
ros::Duration
PFLocalizationNode::resp_
nav_msgs::GetMap::Response resp_
Definition: mrpt_localization_node.h:124
PFLocalizationNode::pub_pose_
ros::Publisher pub_pose_
Definition: mrpt_localization_node.h:133
PFLocalizationNode::Parameters::update_sensor_pose
bool update_sensor_pose
Definition: mrpt_localization_node.h:91
PFLocalizationNode::Parameters::Parameters
Parameters(PFLocalizationNode *p)
Definition: mrpt_localization_node_parameters.cpp:37
PFLocalizationNode::Parameters::node
ros::NodeHandle node
Definition: mrpt_localization_node.h:69
ros::NodeHandle
ros::Subscriber
PFLocalizationNode::tf_broadcaster_
tf2_ros::TransformBroadcaster tf_broadcaster_
Definition: mrpt_localization_node.h:139
PFLocalizationNode::Parameters::use_map_topic
bool use_map_topic
Definition: mrpt_localization_node.h:94
PFLocalizationNode::useROSLogLevel
void useROSLogLevel()
Definition: mrpt_localization_node.cpp:701


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Tue Sep 17 2024 02:10:20