ROS Node. More...
#include <mrpt_localization_node.h>

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) |
| Parameters * | param () |
| 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::CPose3D > | beacon_poses_ |
| ros::ServiceClient | client_map_ |
| bool | first_map_received_ |
| std::map< std::string, mrpt::poses::CPose3D > | laser_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::Subscriber > | sub_sensors_ |
| tf::TransformBroadcaster | tf_broadcaster_ |
| tf::TransformListener | tf_listener_ |
| ros::Time | time_last_input_ |
ROS Node.
Definition at line 60 of file mrpt_localization_node.h.
| PFLocalizationNode::PFLocalizationNode | ( | ros::NodeHandle & | n | ) |
Definition at line 76 of file mrpt_localization_node.cpp.
|
virtual |
Definition at line 75 of file mrpt_localization_node.cpp.
| 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.
Definition at line 474 of file mrpt_localization_node.cpp.
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.
|
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.
|
private |
Definition at line 84 of file mrpt_localization_node.cpp.
|
private |
Definition at line 518 of file mrpt_localization_node.cpp.
|
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.
|
private |
| void PFLocalizationNode::updateMap | ( | const nav_msgs::OccupancyGrid & | _msg | ) |
Definition at line 499 of file mrpt_localization_node.cpp.
|
private |
Definition at line 435 of file mrpt_localization_node.cpp.
|
private |
Definition at line 687 of file mrpt_localization_node.cpp.
|
privatevirtual |
Reimplemented from PFLocalization.
Definition at line 376 of file mrpt_localization_node.cpp.
|
private |
Definition at line 180 of file mrpt_localization_node.cpp.
|
private |
Definition at line 135 of file mrpt_localization_node.h.
|
private |
Definition at line 126 of file mrpt_localization_node.h.
|
private |
Definition at line 118 of file mrpt_localization_node.h.
|
private |
Definition at line 134 of file mrpt_localization_node.h.
|
private |
Definition at line 120 of file mrpt_localization_node.h.
|
private |
Definition at line 62 of file mrpt_localization_node.h.
|
private |
Definition at line 117 of file mrpt_localization_node.h.
|
private |
Definition at line 128 of file mrpt_localization_node.h.
|
private |
Definition at line 129 of file mrpt_localization_node.h.
|
private |
Definition at line 127 of file mrpt_localization_node.h.
|
private |
Definition at line 130 of file mrpt_localization_node.h.
|
private |
Definition at line 121 of file mrpt_localization_node.h.
|
private |
Definition at line 131 of file mrpt_localization_node.h.
|
private |
Definition at line 122 of file mrpt_localization_node.h.
|
private |
Definition at line 125 of file mrpt_localization_node.h.
|
private |
Definition at line 123 of file mrpt_localization_node.h.
|
private |
Definition at line 124 of file mrpt_localization_node.h.
|
private |
Definition at line 133 of file mrpt_localization_node.h.
|
private |
Definition at line 132 of file mrpt_localization_node.h.
|
private |
Definition at line 119 of file mrpt_localization_node.h.