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. | |
| void | publishTF () |
| Publish map -> odom tf; as the filter provides map -> base, we multiply it by base -> odom. | |
| void | updateMap (const nav_msgs::OccupancyGrid &) |
| virtual | ~PFLocalizationNode () |
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 61 of file mrpt_localization_node.h.
Definition at line 63 of file mrpt_localization_node.cpp.
| PFLocalizationNode::~PFLocalizationNode | ( | ) | [virtual] |
Definition at line 62 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::callbackBeacon | ( | const mrpt_msgs::ObservationRangeBeacon & | _msg | ) |
Definition at line 214 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::callbackInitialpose | ( | const geometry_msgs::PoseWithCovarianceStamped & | _msg | ) |
Definition at line 437 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::callbackLaser | ( | const sensor_msgs::LaserScan & | _msg | ) |
Definition at line 179 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::callbackMap | ( | const nav_msgs::OccupancyGrid & | msg | ) |
Definition at line 393 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::callbackOdometry | ( | const nav_msgs::Odometry & | _msg | ) |
Definition at line 446 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::callbackRobotPose | ( | const geometry_msgs::PoseWithCovarianceStamped & | _msg | ) |
Definition at line 250 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::init | ( | ) |
Initializes the parameter with common values to acive a working filter out of the box
Reimplemented from PFLocalization.
Definition at line 76 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::loop | ( | ) |
Definition at line 135 of file mrpt_localization_node.cpp.
| bool PFLocalizationNode::mapCallback | ( | nav_msgs::GetMap::Request & | req, |
| nav_msgs::GetMap::Response & | res | ||
| ) | [private] |
Definition at line 477 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::odometryForCallback | ( | CObservationOdometry::Ptr & | _odometry, |
| const std_msgs::Header & | _msg_header | ||
| ) |
Definition at line 325 of file mrpt_localization_node.cpp.
| PFLocalizationNode::Parameters * PFLocalizationNode::param | ( | ) | [private] |
Definition at line 71 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::publishMap | ( | ) | [private] |
Definition at line 485 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::publishParticles | ( | ) | [private] |
Definition at line 501 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::publishPose | ( | ) |
Publish the current pose of the robot.
Definition at line 610 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 525 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::update | ( | ) | [private] |
| void PFLocalizationNode::updateMap | ( | const nav_msgs::OccupancyGrid & | _msg | ) |
Definition at line 471 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::updateSensorPose | ( | std::string | frame_id | ) | [private] |
Definition at line 406 of file mrpt_localization_node.cpp.
| void PFLocalizationNode::useROSLogLevel | ( | ) | [private] |
Definition at line 651 of file mrpt_localization_node.cpp.
| bool PFLocalizationNode::waitForMap | ( | ) | [private, virtual] |
Reimplemented from PFLocalization.
Definition at line 347 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 154 of file mrpt_localization_node.cpp.
std::map<std::string, mrpt::poses::CPose3D> PFLocalizationNode::beacon_poses_ [private] |
Definition at line 135 of file mrpt_localization_node.h.
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 63 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.
Definition at line 129 of file mrpt_localization_node.h.
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.
Definition at line 131 of file mrpt_localization_node.h.
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.
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.
Definition at line 133 of file mrpt_localization_node.h.
Definition at line 132 of file mrpt_localization_node.h.
Definition at line 119 of file mrpt_localization_node.h.