Public Member Functions | |
RGBDICPOdometry () | |
virtual | ~RGBDICPOdometry () |
![]() | |
const std::string & | frameId () const |
const std::string & | guessFrameId () const |
bool | isPaused () const |
OdometryROS (bool stereoParams, bool visParams, bool icpParams) | |
const std::string & | odomFrameId () const |
const rtabmap::ParametersMap & | parameters () const |
bool | pause (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
void | processData (rtabmap::SensorData &data, const std_msgs::Header &header) |
bool | reset (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
bool | resetToPose (rtabmap_msgs::ResetPose::Request &, rtabmap_msgs::ResetPose::Response &) |
bool | resume (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
bool | setLogDebug (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
bool | setLogError (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
bool | setLogInfo (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
bool | setLogWarn (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
virtual | ~OdometryROS () |
![]() | |
void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) |
Nodelet () | |
virtual | ~Nodelet () |
![]() | |
Handle | getThreadHandle () const |
unsigned long | getThreadId () const |
bool | isCreating () const |
bool | isIdle () const |
bool | isKilled () const |
bool | isRunning () const |
void | join (bool killFirst=false) |
void | kill () |
void | setAffinity (int cpu=0) |
void | setPriority (Priority priority) |
void | start () |
UThread (Priority priority=kPNormal) | |
virtual | ~UThread () |
![]() | |
int | Create (Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const |
int | Create (Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const |
int | Create (unsigned long &ThreadId, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const |
int | Create (unsigned long &ThreadId, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const |
virtual | ~UThreadC () |
virtual | ~UThreadC () |
Private Types | |
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > | MyApproxCloudSyncPolicy |
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > | MyApproxScanSyncPolicy |
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > | MyExactCloudSyncPolicy |
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > | MyExactScanSyncPolicy |
Private Member Functions | |
void | callbackCloud (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::PointCloud2ConstPtr &cloudMsg) |
void | callbackCommon (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &cloudMsg) |
void | callbackScan (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::LaserScanConstPtr &scanMsg) |
virtual void | onOdomInit () |
virtual void | updateParameters (ParametersMap ¶meters) |
Additional Inherited Members | |
![]() | |
enum | Priority |
![]() | |
typedef THREAD_HANDLE | Handle |
typedef THREAD_HANDLE | Handle |
typedef void(* | Handler) () |
typedef void(* | Handler) () |
![]() | |
static unsigned long | currentThreadId () |
![]() | |
static int | Create (const Handler &Function, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) |
static int | Create (const Handler &Function, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) |
static int | Detach (const Handle &H) |
static int | Detach (Handle H) |
static int | Join (const Handle &H) |
static int | Join (Handle H) |
static int | Kill (const Handle &H) |
static int | Kill (Handle H) |
![]() | |
kPAboveNormal | |
kPBelowNormal | |
kPLow | |
kPNormal | |
kPRealTime | |
![]() | |
static void | Exit () |
static void | Exit () |
static int | Self () |
static Handle | Self () |
static void | TestCancel () |
static void | TestCancel () |
Definition at line 66 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 510 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 506 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 512 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 508 of file rgbdicp_odometry.cpp.
|
inline |
Definition at line 69 of file rgbdicp_odometry.cpp.
|
inlinevirtual |
Definition at line 85 of file rgbdicp_odometry.cpp.
|
inlineprivate |
Definition at line 243 of file rgbdicp_odometry.cpp.
|
inlineprivate |
Definition at line 253 of file rgbdicp_odometry.cpp.
|
inlineprivate |
Definition at line 233 of file rgbdicp_odometry.cpp.
|
inlineprotectedvirtual |
Implements rtabmap_odom::OdometryROS.
Definition at line 471 of file rgbdicp_odometry.cpp.
|
inlineprivatevirtual |
Implements rtabmap_odom::OdometryROS.
Definition at line 107 of file rgbdicp_odometry.cpp.
|
inlineprivatevirtual |
Reimplemented from rtabmap_odom::OdometryROS.
Definition at line 222 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 511 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 507 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 505 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 513 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 509 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 502 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 501 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 503 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 516 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 514 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 504 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 517 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 519 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 520 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 518 of file rgbdicp_odometry.cpp.
|
private |
Definition at line 515 of file rgbdicp_odometry.cpp.