|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
This class contains the ros interfaces for CurrentStateMontior. More...
#include <current_state_monitor_middleware_handle.hpp>


Public Member Functions | |
| CurrentStateMonitorMiddlewareHandle (const rclcpp::Node::SharedPtr &node) | |
| Constructor. | |
| rclcpp::Time | now () const override |
| Get the current time. | |
| void | createJointStateSubscription (const std::string &topic, JointStateUpdateCallback callback) override |
| Creates a joint state subscription. | |
| void | createStaticTfSubscription (std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> callback) override |
| Creates a static transform message subscription. | |
| void | createDynamicTfSubscription (std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> callback) override |
| Creates a dynamic transform message subscription. | |
| void | resetJointStateSubscription () override |
| Reset the joint state subscription. | |
| std::string | getJointStateTopicName () const override |
| Get the joint state topic name. | |
| bool | sleepFor (const std::chrono::nanoseconds &nanoseconds) const override |
| Uses rclcpp::sleep_for to sleep. | |
| bool | ok () const override |
| Uses rclcpp::ok to check the context status. | |
| std::string | getStaticTfTopicName () const override |
| Get the static transform topic name. | |
| std::string | getDynamicTfTopicName () const override |
| Get the dynamic transform topic name. | |
| void | resetTfSubscriptions () override |
| Reset the static & dynamic transform subscriptions. | |
Public Member Functions inherited from planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle | |
| virtual | ~MiddlewareHandle ()=default |
| Destroys the object. | |
| virtual void | createStaticTfSubscription (TfCallback callback)=0 |
| Creates a static transform message subscription. | |
| virtual void | createDynamicTfSubscription (TfCallback callback)=0 |
| Creates a dynamic transform message subscription. | |
Additional Inherited Members | |
Public Types inherited from planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle | |
| using | TfCallback = std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> |
This class contains the ros interfaces for CurrentStateMontior.
Definition at line 52 of file current_state_monitor_middleware_handle.hpp.
| planning_scene_monitor::CurrentStateMonitorMiddlewareHandle::CurrentStateMonitorMiddlewareHandle | ( | const rclcpp::Node::SharedPtr & | node | ) |
Constructor.
| [in] | node | The ros node |
Definition at line 60 of file current_state_monitor_middleware_handle.cpp.
|
override |
Creates a dynamic transform message subscription.
| [in] | callback | The callback |
Definition at line 104 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Creates a joint state subscription.
| [in] | topic | The topic |
| [in] | callback | The callback |
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 70 of file current_state_monitor_middleware_handle.cpp.
|
override |
Creates a static transform message subscription.
| [in] | callback | The callback |
Definition at line 110 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Get the dynamic transform topic name.
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 121 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Get the joint state topic name.
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 82 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Get the static transform topic name.
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 116 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Get the current time.
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 65 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Uses rclcpp::ok to check the context status.
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 99 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Reset the joint state subscription.
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 77 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Reset the static & dynamic transform subscriptions.
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 126 of file current_state_monitor_middleware_handle.cpp.
|
overridevirtual |
Uses rclcpp::sleep_for to sleep.
| [in] | nanoseconds | The nanoseconds to sleep for |
Implements planning_scene_monitor::CurrentStateMonitor::MiddlewareHandle.
Definition at line 94 of file current_state_monitor_middleware_handle.cpp.