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_ |
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 | |
Parameters * | param_ |
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... | |
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 239 of file mrpt_localization_node.cpp.
void PFLocalizationNode::callbackInitialpose | ( | const geometry_msgs::PoseWithCovarianceStamped & | _msg | ) |
Definition at line 459 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 416 of file mrpt_localization_node.cpp.
void PFLocalizationNode::callbackOdometry | ( | const nav_msgs::Odometry & | _msg | ) |
Definition at line 468 of file mrpt_localization_node.cpp.
void PFLocalizationNode::callbackRobotPose | ( | const geometry_msgs::PoseWithCovarianceStamped & | _msg | ) |
Definition at line 274 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 504 of file mrpt_localization_node.cpp.
void PFLocalizationNode::odometryForCallback | ( | CObservationOdometry::Ptr & | _odometry, |
const std_msgs::Header & | _msg_header | ||
) |
Definition at line 348 of file mrpt_localization_node.cpp.
|
private |
Definition at line 84 of file mrpt_localization_node.cpp.
|
private |
Definition at line 512 of file mrpt_localization_node.cpp.
|
private |
Definition at line 528 of file mrpt_localization_node.cpp.
void PFLocalizationNode::publishPose | ( | ) |
Publish the current pose of the robot.
Definition at line 637 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 552 of file mrpt_localization_node.cpp.
|
private |
void PFLocalizationNode::updateMap | ( | const nav_msgs::OccupancyGrid & | _msg | ) |
Definition at line 493 of file mrpt_localization_node.cpp.
|
private |
Definition at line 429 of file mrpt_localization_node.cpp.
|
private |
Definition at line 681 of file mrpt_localization_node.cpp.
|
privatevirtual |
Reimplemented from PFLocalization.
Definition at line 370 of file mrpt_localization_node.cpp.
|
private |
Definition at line 180 of file mrpt_localization_node.cpp.
|
private |
Definition at line 134 of file mrpt_localization_node.h.
|
private |
Definition at line 125 of file mrpt_localization_node.h.
|
private |
Definition at line 117 of file mrpt_localization_node.h.
|
private |
Definition at line 133 of file mrpt_localization_node.h.
|
private |
Definition at line 119 of file mrpt_localization_node.h.
|
private |
Definition at line 62 of file mrpt_localization_node.h.
|
private |
Definition at line 116 of file mrpt_localization_node.h.
|
private |
Definition at line 127 of file mrpt_localization_node.h.
|
private |
Definition at line 128 of file mrpt_localization_node.h.
|
private |
Definition at line 126 of file mrpt_localization_node.h.
|
private |
Definition at line 129 of file mrpt_localization_node.h.
|
private |
Definition at line 120 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 124 of file mrpt_localization_node.h.
|
private |
Definition at line 122 of file mrpt_localization_node.h.
|
private |
Definition at line 123 of file mrpt_localization_node.h.
|
private |
Definition at line 132 of file mrpt_localization_node.h.
|
private |
Definition at line 131 of file mrpt_localization_node.h.
|
private |
Definition at line 118 of file mrpt_localization_node.h.