mrpt_localization_node.h
Go to the documentation of this file.
00001 /***********************************************************************************
00002  * Revised BSD License *
00003  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
00004  * All rights reserved. *
00005  *                                                                                 *
00006  * Redistribution and use in source and binary forms, with or without *
00007  * modification, are permitted provided that the following conditions are met: *
00008  *     * Redistributions of source code must retain the above copyright *
00009  *       notice, this list of conditions and the following disclaimer. *
00010  *     * Redistributions in binary form must reproduce the above copyright *
00011  *       notice, this list of conditions and the following disclaimer in the *
00012  *       documentation and/or other materials provided with the distribution. *
00013  *     * Neither the name of the Vienna University of Technology nor the *
00014  *       names of its contributors may be used to endorse or promote products *
00015  *       derived from this software without specific prior written permission. *
00016  *                                                                                 *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  *AND *
00019  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020  **
00021  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
00022  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
00023  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
00024  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  **
00026  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
00027  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
00028  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00029  **
00030  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00031  **                       *
00032  ***********************************************************************************/
00033 
00034 #ifndef MRPT_LOCALIZATION_NODE_H
00035 #define MRPT_LOCALIZATION_NODE_H
00036 
00037 #include <cstring>  // size_t
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/version.h>
00052 #include <mrpt/obs/CObservationOdometry.h>
00053 using mrpt::obs::CObservationOdometry;
00054 
00055 #include "mrpt_localization/MotionConfig.h"
00056 #include "mrpt_localization/mrpt_localization.h"
00057 #include "mrpt_msgs/ObservationRangeBeacon.h"
00058 
00060 class PFLocalizationNode : public PFLocalization
00061 {
00062         MRPT_ROS_LOG_MACROS;
00063 
00064    public:
00065         struct Parameters : public PFLocalization::Parameters
00066         {
00067                 static const int MOTION_MODEL_GAUSSIAN = 0;
00068                 static const int MOTION_MODEL_THRUN = 1;
00069                 Parameters(PFLocalizationNode* p);
00070                 ros::NodeHandle node;
00071                 void callbackParameters(
00072                         mrpt_localization::MotionConfig& config, uint32_t level);
00073                 dynamic_reconfigure::Server<mrpt_localization::MotionConfig>
00074                         reconfigure_server_;
00075                 dynamic_reconfigure::Server<
00076                         mrpt_localization::MotionConfig>::CallbackType reconfigure_cb_;
00077                 void update(const unsigned long& loop_count);
00078                 double rate;
00079                 double transform_tolerance;  
00080 
00081                 double no_update_tolerance;  
00082 
00083                 double no_inputs_tolerance;  
00084 
00085                 int parameter_update_skip;
00086                 int particlecloud_update_skip;
00087                 int map_update_skip;
00088                 std::string tf_prefix;
00089                 std::string base_frame_id;
00090                 std::string odom_frame_id;
00091                 std::string global_frame_id;
00092                 bool update_while_stopped;
00093                 bool pose_broadcast;
00094                 bool tf_broadcast;
00095                 bool use_map_topic;
00096                 bool first_map_only;
00097         };
00098 
00099         PFLocalizationNode(ros::NodeHandle& n);
00100         virtual ~PFLocalizationNode();
00101         void init();
00102         void loop();
00103         void callbackLaser(const sensor_msgs::LaserScan&);
00104         void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon&);
00105         void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped&);
00106         void odometryForCallback(
00107                 CObservationOdometry::Ptr&, const std_msgs::Header&);
00108         void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped&);
00109         void callbackOdometry(const nav_msgs::Odometry&);
00110         void callbackMap(const nav_msgs::OccupancyGrid&);
00111         void updateMap(const nav_msgs::OccupancyGrid&);
00112         void publishTF();
00113         void publishPose();
00114 
00115    private:
00116         ros::NodeHandle nh_;
00117         bool first_map_received_;
00118         ros::Time time_last_input_;
00119         unsigned long long loop_count_;
00120         nav_msgs::GetMap::Response resp_;
00121         ros::Subscriber sub_init_pose_;
00122         ros::Subscriber sub_odometry_;
00123         std::vector<ros::Subscriber> sub_sensors_;
00124         ros::Subscriber sub_map_;
00125         ros::ServiceClient client_map_;
00126         ros::Publisher pub_particles_;
00127         ros::Publisher pub_map_;
00128         ros::Publisher pub_metadata_;
00129         ros::Publisher pub_pose_;
00130         ros::ServiceServer service_map_;
00131         tf::TransformListener tf_listener_;
00132         tf::TransformBroadcaster tf_broadcaster_;
00133         std::map<std::string, mrpt::poses::CPose3D> laser_poses_;
00134         std::map<std::string, mrpt::poses::CPose3D> beacon_poses_;
00135 
00136         // methods
00137         Parameters* param();
00138         void update();
00139         void updateSensorPose(std::string frame_id);
00140 
00141         void publishParticles();
00142         void useROSLogLevel();
00143 
00144         bool waitForTransform(
00145                 mrpt::poses::CPose3D& des, const std::string& target_frame,
00146                 const std::string& source_frame, const ros::Time& time,
00147                 const ros::Duration& timeout,
00148                 const ros::Duration& polling_sleep_duration = ros::Duration(0.01));
00149         bool mapCallback(
00150                 nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res);
00151         void publishMap();
00152         virtual bool waitForMap();
00153 };
00154 
00155 #endif  // MRPT_LOCALIZATION_NODE_H


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Thu Jun 6 2019 21:53:18