Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
PFLocalizationNode Class Reference

ROS Node. More...

#include <mrpt_localization_node.h>

Inheritance diagram for PFLocalizationNode:
Inheritance graph
[legend]

Classes

struct  Parameters
 

Public Member Functions

void callbackBeacon (const mrpt_msgs::ObservationRangeBeacon &)
 
void callbackInitialpose (const geometry_msgs::PoseWithCovarianceStamped &)
 
void callbackLaser (const sensor_msgs::LaserScan &)
 
void callbackMap (const nav_msgs::OccupancyGrid &)
 
void callbackOdometry (const nav_msgs::Odometry &)
 
void callbackRobotPose (const geometry_msgs::PoseWithCovarianceStamped &)
 
void init ()
 
void loop ()
 
void odometryForCallback (CObservationOdometry::Ptr &, const std_msgs::Header &)
 
 PFLocalizationNode (ros::NodeHandle &n)
 
void publishPose ()
 Publish the current pose of the robot. More...
 
void publishTF ()
 Publish map -> odom tf; as the filter provides map -> base, we multiply it by base -> odom. More...
 
void updateMap (const nav_msgs::OccupancyGrid &)
 
virtual ~PFLocalizationNode ()
 
- Public Member Functions inherited from PFLocalization
 PFLocalization (Parameters *parm)
 
virtual ~PFLocalization ()
 
- Public Member Functions inherited from PFLocalizationCore
void init ()
 
void observation (CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
 
 PFLocalizationCore ()
 
 ~PFLocalizationCore ()
 

Private Member Functions

bool mapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
 
Parametersparam ()
 
void publishMap ()
 
void publishParticles ()
 
void update ()
 
void updateSensorPose (std::string frame_id)
 
void useROSLogLevel ()
 
virtual bool waitForMap ()
 
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))
 

Private Attributes

std::map< std::string, mrpt::poses::CPose3Dbeacon_poses_
 
ros::ServiceClient client_map_
 
bool first_map_received_
 
std::map< std::string, mrpt::poses::CPose3Dlaser_poses_
 
unsigned long long loop_count_
 
 MRPT_ROS_LOG_MACROS
 
ros::NodeHandle nh_
 
ros::Publisher pub_map_
 
ros::Publisher pub_metadata_
 
ros::Publisher pub_particles_
 
ros::Publisher pub_pose_
 
nav_msgs::GetMap::Response resp_
 
ros::ServiceServer service_map_
 
ros::Subscriber sub_init_pose_
 
ros::Subscriber sub_map_
 
ros::Subscriber sub_odometry_
 
std::vector< ros::Subscribersub_sensors_
 
tf::TransformBroadcaster tf_broadcaster_
 
tf::TransformListener tf_listener_
 
ros::Time time_last_input_
 

Additional Inherited Members

- Public Types inherited from PFLocalizationCore
enum  PFStates { NA, INIT, RUN, IDLE }
 
- Protected Member Functions inherited from PFLocalization
void configureFilter (const CConfigFile &_configFile)
 
void init ()
 
void init3DDebug ()
 
void show3DDebug (CSensoryFrame::Ptr _observations)
 
- Protected Attributes inherited from PFLocalization
Parametersparam_
 
bool SCENE3D_FOLLOW_
 
int SCENE3D_FREQ_
 
mrpt::opengl::COpenGLScene scene_
 
bool SHOW_PROGRESS_3D_REAL_TIME_
 
int SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS_
 
mrpt::gui::CDisplayWindow3D::Ptr win3D_
 
- Protected Attributes inherited from PFLocalizationCore
float init_PDF_max_x
 
float init_PDF_max_y
 
float init_PDF_min_x
 any cell More...
 
float init_PDF_min_y
 
bool init_PDF_mode
 
int initial_particle_count_
 number of particles for initialization More...
 
mrpt::poses::CPosePDFGaussian initial_pose_
 initial posed used in initializeFilter() More...
 
CMultiMetricMap metric_map_
 map More...
 
CActionRobotMovement2D::TMotionModelOptions motion_model_default_options_
 used if there are is not odom More...
 
CActionRobotMovement2D::TMotionModelOptions motion_model_options_
 used with odom value motion noise More...
 
mrpt::poses::CPose2D odom_last_observation_
 correct time More...
 
mrpt::slam::CMonteCarloLocalization2D pdf_
 the filter More...
 
mrpt::bayes::CParticleFilter pf_
 common interface for particle filters More...
 
mrpt::bayes::CParticleFilter::TParticleFilterStats pf_stats_
 filter statistics More...
 
PFStates state_
 updates More...
 
mrpt::utils::CTicTac tictac_
 timer to measure performance More...
 
mrpt::system::TTimeStamp time_last_update_
 time of the last update More...
 
size_t update_counter_
 
bool use_motion_model_default_options_
 used default odom_params More...
 

Detailed Description

ROS Node.

Definition at line 60 of file mrpt_localization_node.h.

Constructor & Destructor Documentation

PFLocalizationNode::PFLocalizationNode ( ros::NodeHandle n)

Definition at line 76 of file mrpt_localization_node.cpp.

PFLocalizationNode::~PFLocalizationNode ( )
virtual

Definition at line 75 of file mrpt_localization_node.cpp.

Member Function Documentation

void PFLocalizationNode::callbackBeacon ( const mrpt_msgs::ObservationRangeBeacon _msg)

Definition at line 242 of file mrpt_localization_node.cpp.

void PFLocalizationNode::callbackInitialpose ( const geometry_msgs::PoseWithCovarianceStamped &  _msg)

Definition at line 465 of file mrpt_localization_node.cpp.

void PFLocalizationNode::callbackLaser ( const sensor_msgs::LaserScan _msg)

Definition at line 205 of file mrpt_localization_node.cpp.

void PFLocalizationNode::callbackMap ( const nav_msgs::OccupancyGrid msg)

Definition at line 422 of file mrpt_localization_node.cpp.

void PFLocalizationNode::callbackOdometry ( const nav_msgs::Odometry &  _msg)

Definition at line 474 of file mrpt_localization_node.cpp.

void PFLocalizationNode::callbackRobotPose ( const geometry_msgs::PoseWithCovarianceStamped &  _msg)

Definition at line 280 of file mrpt_localization_node.cpp.

void PFLocalizationNode::init ( )

Definition at line 89 of file mrpt_localization_node.cpp.

void PFLocalizationNode::loop ( )

Definition at line 156 of file mrpt_localization_node.cpp.

bool PFLocalizationNode::mapCallback ( nav_msgs::GetMap::Request &  req,
nav_msgs::GetMap::Response &  res 
)
private

Definition at line 510 of file mrpt_localization_node.cpp.

void PFLocalizationNode::odometryForCallback ( CObservationOdometry::Ptr &  _odometry,
const std_msgs::Header _msg_header 
)

Definition at line 354 of file mrpt_localization_node.cpp.

PFLocalizationNode::Parameters * PFLocalizationNode::param ( )
private

Definition at line 84 of file mrpt_localization_node.cpp.

void PFLocalizationNode::publishMap ( )
private

Definition at line 518 of file mrpt_localization_node.cpp.

void PFLocalizationNode::publishParticles ( )
private

Definition at line 534 of file mrpt_localization_node.cpp.

void PFLocalizationNode::publishPose ( )

Publish the current pose of the robot.

Definition at line 643 of file mrpt_localization_node.cpp.

void PFLocalizationNode::publishTF ( )

Publish map -> odom tf; as the filter provides map -> base, we multiply it by base -> odom.

Definition at line 558 of file mrpt_localization_node.cpp.

void PFLocalizationNode::update ( )
private
void PFLocalizationNode::updateMap ( const nav_msgs::OccupancyGrid _msg)

Definition at line 499 of file mrpt_localization_node.cpp.

void PFLocalizationNode::updateSensorPose ( std::string  frame_id)
private

Definition at line 435 of file mrpt_localization_node.cpp.

void PFLocalizationNode::useROSLogLevel ( )
private

Definition at line 687 of file mrpt_localization_node.cpp.

bool PFLocalizationNode::waitForMap ( )
privatevirtual

Reimplemented from PFLocalization.

Definition at line 376 of file mrpt_localization_node.cpp.

bool PFLocalizationNode::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) 
)
private

Definition at line 180 of file mrpt_localization_node.cpp.

Member Data Documentation

std::map<std::string, mrpt::poses::CPose3D> PFLocalizationNode::beacon_poses_
private

Definition at line 135 of file mrpt_localization_node.h.

ros::ServiceClient PFLocalizationNode::client_map_
private

Definition at line 126 of file mrpt_localization_node.h.

bool PFLocalizationNode::first_map_received_
private

Definition at line 118 of file mrpt_localization_node.h.

std::map<std::string, mrpt::poses::CPose3D> PFLocalizationNode::laser_poses_
private

Definition at line 134 of file mrpt_localization_node.h.

unsigned long long PFLocalizationNode::loop_count_
private

Definition at line 120 of file mrpt_localization_node.h.

PFLocalizationNode::MRPT_ROS_LOG_MACROS
private

Definition at line 62 of file mrpt_localization_node.h.

ros::NodeHandle PFLocalizationNode::nh_
private

Definition at line 117 of file mrpt_localization_node.h.

ros::Publisher PFLocalizationNode::pub_map_
private

Definition at line 128 of file mrpt_localization_node.h.

ros::Publisher PFLocalizationNode::pub_metadata_
private

Definition at line 129 of file mrpt_localization_node.h.

ros::Publisher PFLocalizationNode::pub_particles_
private

Definition at line 127 of file mrpt_localization_node.h.

ros::Publisher PFLocalizationNode::pub_pose_
private

Definition at line 130 of file mrpt_localization_node.h.

nav_msgs::GetMap::Response PFLocalizationNode::resp_
private

Definition at line 121 of file mrpt_localization_node.h.

ros::ServiceServer PFLocalizationNode::service_map_
private

Definition at line 131 of file mrpt_localization_node.h.

ros::Subscriber PFLocalizationNode::sub_init_pose_
private

Definition at line 122 of file mrpt_localization_node.h.

ros::Subscriber PFLocalizationNode::sub_map_
private

Definition at line 125 of file mrpt_localization_node.h.

ros::Subscriber PFLocalizationNode::sub_odometry_
private

Definition at line 123 of file mrpt_localization_node.h.

std::vector<ros::Subscriber> PFLocalizationNode::sub_sensors_
private

Definition at line 124 of file mrpt_localization_node.h.

tf::TransformBroadcaster PFLocalizationNode::tf_broadcaster_
private

Definition at line 133 of file mrpt_localization_node.h.

tf::TransformListener PFLocalizationNode::tf_listener_
private

Definition at line 132 of file mrpt_localization_node.h.

ros::Time PFLocalizationNode::time_last_input_
private

Definition at line 119 of file mrpt_localization_node.h.


The documentation for this class was generated from the following files:


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Thu Mar 12 2020 03:21:48