
Public Member Functions | |
| ICPOdometry () | |
| virtual | ~ICPOdometry () |
Public Member Functions inherited from rtabmap_odom::OdometryROS | |
| 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 () |
Public Member Functions inherited from nodelet::Nodelet | |
| 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 () |
Public Member Functions inherited from UThread | |
| 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 () |
Public Member Functions inherited from UThreadC< void > | |
| 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 Member Functions | |
| void | callbackCloud (const sensor_msgs::PointCloud2ConstPtr &pointCloudMsg) |
| void | callbackScan (const sensor_msgs::LaserScanConstPtr &scanMsg) |
| virtual void | onOdomInit () |
| virtual void | updateParameters (ParametersMap ¶meters) |
Private Attributes | |
| ros::Subscriber | cloud_sub_ |
| bool | cloudReceived_ = false |
| bool | deskewing_ |
| bool | deskewingSlerp_ |
| ros::Publisher | filtered_scan_pub_ |
| pluginlib::ClassLoader< rtabmap_odom::PluginInterface > | plugin_loader_ |
| std::vector< boost::shared_ptr< rtabmap_odom::PluginInterface > > | plugins_ |
| ros::Subscriber | scan_sub_ |
| bool | scanCloudIs2d_ |
| int | scanCloudMaxPoints_ |
| int | scanDownsamplingStep_ |
| double | scanNormalGroundUp_ |
| int | scanNormalK_ |
| double | scanNormalRadius_ |
| double | scanRangeMax_ |
| double | scanRangeMin_ |
| bool | scanReceived_ = false |
| double | scanVoxelSize_ |
Additional Inherited Members | |
Public Types inherited from UThread | |
| enum | Priority |
Public Types inherited from UThreadC< void > | |
| typedef THREAD_HANDLE | Handle |
| typedef THREAD_HANDLE | Handle |
| typedef void(* | Handler) () |
| typedef void(* | Handler) () |
Static Public Member Functions inherited from UThread | |
| static unsigned long | currentThreadId () |
Static Public Member Functions inherited from UThreadC< void > | |
| 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) |
Public Attributes inherited from UThread | |
| kPAboveNormal | |
| kPBelowNormal | |
| kPLow | |
| kPNormal | |
| kPRealTime | |
Static Protected Member Functions inherited from UThreadC< void > | |
| static void | Exit () |
| static void | Exit () |
| static int | Self () |
| static Handle | Self () |
| static void | TestCancel () |
| static void | TestCancel () |
Definition at line 59 of file icp_odometry.cpp.
|
inline |
Definition at line 62 of file icp_odometry.cpp.
|
inlinevirtual |
Definition at line 81 of file icp_odometry.cpp.
|
inlineprivate |
Definition at line 566 of file icp_odometry.cpp.
|
inlineprivate |
Definition at line 326 of file icp_odometry.cpp.
|
inlineprotectedvirtual |
Implements rtabmap_odom::OdometryROS.
Definition at line 885 of file icp_odometry.cpp.
|
inlineprivatevirtual |
Implements rtabmap_odom::OdometryROS.
Definition at line 88 of file icp_odometry.cpp.
|
inlineprotectedvirtual |
Reimplemented from rtabmap_odom::OdometryROS.
Definition at line 890 of file icp_odometry.cpp.
|
inlineprivatevirtual |
Reimplemented from rtabmap_odom::OdometryROS.
Definition at line 167 of file icp_odometry.cpp.
|
private |
Definition at line 903 of file icp_odometry.cpp.
|
private |
Definition at line 919 of file icp_odometry.cpp.
|
private |
Definition at line 914 of file icp_odometry.cpp.
|
private |
Definition at line 915 of file icp_odometry.cpp.
|
private |
Definition at line 904 of file icp_odometry.cpp.
|
private |
Definition at line 917 of file icp_odometry.cpp.
|
private |
Definition at line 916 of file icp_odometry.cpp.
|
private |
Definition at line 902 of file icp_odometry.cpp.
|
private |
Definition at line 906 of file icp_odometry.cpp.
|
private |
Definition at line 905 of file icp_odometry.cpp.
|
private |
Definition at line 907 of file icp_odometry.cpp.
|
private |
Definition at line 913 of file icp_odometry.cpp.
|
private |
Definition at line 911 of file icp_odometry.cpp.
|
private |
Definition at line 912 of file icp_odometry.cpp.
|
private |
Definition at line 909 of file icp_odometry.cpp.
|
private |
Definition at line 908 of file icp_odometry.cpp.
|
private |
Definition at line 918 of file icp_odometry.cpp.
|
private |
Definition at line 910 of file icp_odometry.cpp.