Definition at line 48 of file stereo_throttle.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> rtabmap_ros::StereoThrottleNodelet::MyApproxSyncPolicy [private] |
Definition at line 235 of file stereo_throttle.cpp.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> rtabmap_ros::StereoThrottleNodelet::MyExactSyncPolicy [private] |
Definition at line 237 of file stereo_throttle.cpp.
Definition at line 52 of file stereo_throttle.cpp.
virtual rtabmap_ros::StereoThrottleNodelet::~StereoThrottleNodelet | ( | ) | [inline, virtual] |
Definition at line 60 of file stereo_throttle.cpp.
void rtabmap_ros::StereoThrottleNodelet::callback | ( | const sensor_msgs::ImageConstPtr & | imageLeft, |
const sensor_msgs::ImageConstPtr & | imageRight, | ||
const sensor_msgs::CameraInfoConstPtr & | camInfoLeft, | ||
const sensor_msgs::CameraInfoConstPtr & | camInfoRight | ||
) | [inline, private] |
Definition at line 122 of file stereo_throttle.cpp.
virtual void rtabmap_ros::StereoThrottleNodelet::onInit | ( | ) | [inline, private, virtual] |
Implements nodelet::Nodelet.
Definition at line 75 of file stereo_throttle.cpp.
message_filters::Synchronizer<MyApproxSyncPolicy>* rtabmap_ros::StereoThrottleNodelet::approxSync_ [private] |
Definition at line 236 of file stereo_throttle.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::StereoThrottleNodelet::cameraInfoLeft_ [private] |
Definition at line 232 of file stereo_throttle.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::StereoThrottleNodelet::cameraInfoRight_ [private] |
Definition at line 233 of file stereo_throttle.cpp.
int rtabmap_ros::StereoThrottleNodelet::decimation_ [private] |
Definition at line 240 of file stereo_throttle.cpp.
message_filters::Synchronizer<MyExactSyncPolicy>* rtabmap_ros::StereoThrottleNodelet::exactSync_ [private] |
Definition at line 238 of file stereo_throttle.cpp.
Definition at line 230 of file stereo_throttle.cpp.
Definition at line 225 of file stereo_throttle.cpp.
Definition at line 231 of file stereo_throttle.cpp.
Definition at line 226 of file stereo_throttle.cpp.
Definition at line 227 of file stereo_throttle.cpp.
Definition at line 228 of file stereo_throttle.cpp.
Definition at line 73 of file stereo_throttle.cpp.
double rtabmap_ros::StereoThrottleNodelet::rate_ [private] |
Definition at line 74 of file stereo_throttle.cpp.