43 #include <rclcpp/rclcpp.hpp>
47 #include <sensor_msgs/msg/joint_state.hpp>
48 #include <std_msgs/msg/float64.hpp>
84 const std::shared_ptr<rclcpp::Node> node_;
90 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
93 std::shared_ptr<moveit::core::RobotState> current_state_;
98 double velocity_scale_ = 1;
99 double self_collision_distance_ = 0;
100 double scene_collision_distance_ = 0;
101 bool collision_detected_ =
false;
102 bool paused_ =
false;
104 const double self_velocity_scale_coefficient_;
105 const double scene_velocity_scale_coefficient_;
112 rclcpp::TimerBase::SharedPtr timer_;
114 rclcpp::Publisher<std_msgs::msg::Float64>::SharedPtr collision_velocity_scale_pub_;
116 mutable std::mutex joint_state_mutex_;
117 sensor_msgs::msg::JointState latest_joint_state_;
CollisionCheck(const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr ¶meters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Constructor.
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
void start()
start the Timer that regulates collision check rate
Representation of a collision checking request.
Representation of a collision checking result.
std::shared_ptr< const ServoParameters > SharedConstPtr