#include <base.h>
Classes | |
struct | Params |
Public Member Functions | |
void | finalize () |
Finalize stereo slam node. | |
Params | params () const |
void | setParams (const Params ¶ms) |
SlamBase (ros::NodeHandle nh, ros::NodeHandle nhp) | |
Class constructor. Reads node parameters and initialize some properties. | |
Protected Member Functions | |
void | init () |
Initializes the stereo slam node. | |
void | msgsCallback (const nav_msgs::Odometry::ConstPtr &odom_msg, const sensor_msgs::ImageConstPtr &l_img_msg, const sensor_msgs::ImageConstPtr &r_img_msg, const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg) |
Messages callback. This function is called when synchronized odometry and image message are received. | |
void | msgsCallback (const nav_msgs::Odometry::ConstPtr &odom_msg, const sensor_msgs::ImageConstPtr &l_img_msg, const sensor_msgs::ImageConstPtr &r_img_msg, const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg, const sensor_msgs::PointCloud2ConstPtr &cloud_msg) |
Messages callback. This function is called when synchronized odometry and image message are received. | |
void | readParameters () |
Reads the stereo slam node parameters. | |
Protected Attributes | |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_private_ |
Private Types | |
typedef message_filters::sync_policies::ExactTime < nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > | ExactPolicyCloud |
typedef message_filters::sync_policies::ExactTime < nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > | ExactPolicyNoCloud |
typedef message_filters::Synchronizer < ExactPolicyCloud > | ExactSyncCloud |
typedef message_filters::Synchronizer < ExactPolicyNoCloud > | ExactSyncNoCloud |
Private Attributes | |
message_filters::Subscriber < sensor_msgs::PointCloud2 > | cloud_sub_ |
boost::shared_ptr< ExactSyncCloud > | exact_sync_cloud_ |
boost::shared_ptr < ExactSyncNoCloud > | exact_sync_no_cloud_ |
bool | first_iter_ |
> Graph object | |
slam::Graph | graph_ |
> Pose object | |
haloc::LoopClosure | lc_ |
> Stores parameters | |
message_filters::Subscriber < sensor_msgs::CameraInfo > | left_info_sub_ |
image_transport::SubscriberFilter | left_sub_ |
message_filters::Subscriber < nav_msgs::Odometry > | odom_sub_ |
Params | params_ |
PointCloud | pcl_cloud_ |
> Indicates first iteration | |
slam::Pose | pose_ |
> Loop closure object | |
message_filters::Subscriber < sensor_msgs::CameraInfo > | right_info_sub_ |
image_transport::SubscriberFilter | right_sub_ |
typedef message_filters::sync_policies::ExactTime<nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> slam::SlamBase::ExactPolicyCloud [private] |
typedef message_filters::sync_policies::ExactTime<nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> slam::SlamBase::ExactPolicyNoCloud [private] |
typedef message_filters::Synchronizer<ExactPolicyCloud> slam::SlamBase::ExactSyncCloud [private] |
typedef message_filters::Synchronizer<ExactPolicyNoCloud> slam::SlamBase::ExactSyncNoCloud [private] |
slam::SlamBase::SlamBase | ( | ros::NodeHandle | nh, |
ros::NodeHandle | nhp | ||
) |
void slam::SlamBase::finalize | ( | ) |
void slam::SlamBase::init | ( | ) | [protected] |
void slam::SlamBase::msgsCallback | ( | const nav_msgs::Odometry::ConstPtr & | odom_msg, |
const sensor_msgs::ImageConstPtr & | l_img_msg, | ||
const sensor_msgs::ImageConstPtr & | r_img_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | l_info_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | r_info_msg | ||
) | [protected] |
Messages callback. This function is called when synchronized odometry and image message are received.
odom_msg | ros odometry message of type nav_msgs::Odometry |
l_img | left stereo image message of type sensor_msgs::Image |
r_img | right stereo image message of type sensor_msgs::Image |
l_info | left stereo info message of type sensor_msgs::CameraInfo |
r_info | right stereo info message of type sensor_msgs::CameraInfo |
void slam::SlamBase::msgsCallback | ( | const nav_msgs::Odometry::ConstPtr & | odom_msg, |
const sensor_msgs::ImageConstPtr & | l_img_msg, | ||
const sensor_msgs::ImageConstPtr & | r_img_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | l_info_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | r_info_msg, | ||
const sensor_msgs::PointCloud2ConstPtr & | cloud_msg | ||
) | [protected] |
Messages callback. This function is called when synchronized odometry and image message are received.
odom_msg | ros odometry message of type nav_msgs::Odometry |
l_img | left stereo image message of type sensor_msgs::Image |
r_img | right stereo image message of type sensor_msgs::Image |
l_info | left stereo info message of type sensor_msgs::CameraInfo |
r_info | right stereo info message of type sensor_msgs::CameraInfo |
cloud_msg | ros pointcloud message of type sensor_msgs::PointCloud2 |
Params slam::SlamBase::params | ( | ) | const [inline] |
void slam::SlamBase::readParameters | ( | ) | [protected] |
void slam::SlamBase::setParams | ( | const Params & | params | ) | [inline] |
message_filters::Subscriber<sensor_msgs::PointCloud2> slam::SlamBase::cloud_sub_ [private] |
boost::shared_ptr<ExactSyncCloud> slam::SlamBase::exact_sync_cloud_ [private] |
boost::shared_ptr<ExactSyncNoCloud> slam::SlamBase::exact_sync_no_cloud_ [private] |
bool slam::SlamBase::first_iter_ [private] |
slam::Graph slam::SlamBase::graph_ [private] |
haloc::LoopClosure slam::SlamBase::lc_ [private] |
message_filters::Subscriber<sensor_msgs::CameraInfo> slam::SlamBase::left_info_sub_ [private] |
ros::NodeHandle slam::SlamBase::nh_ [protected] |
ros::NodeHandle slam::SlamBase::nh_private_ [protected] |
message_filters::Subscriber<nav_msgs::Odometry> slam::SlamBase::odom_sub_ [private] |
Params slam::SlamBase::params_ [private] |
PointCloud slam::SlamBase::pcl_cloud_ [private] |
slam::Pose slam::SlamBase::pose_ [private] |
message_filters::Subscriber<sensor_msgs::CameraInfo> slam::SlamBase::right_info_sub_ [private] |