38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
43 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_collision_detection.collision_robot");
45 static inline bool validateScale(
const double scale)
47 if (scale < std::numeric_limits<double>::epsilon())
49 RCLCPP_ERROR(LOGGER,
"Scale must be positive");
52 if (scale > std::numeric_limits<double>::max())
54 RCLCPP_ERROR(LOGGER,
"Scale must be finite");
60 static inline bool validatePadding(
const double padding)
64 RCLCPP_ERROR(LOGGER,
"Padding cannot be negative");
67 if (padding > std::numeric_limits<double>::max())
69 RCLCPP_ERROR(LOGGER,
"Padding must be finite");
78 : robot_model_(model), world_(std::make_shared<
World>()), world_const_(world_)
80 if (!validateScale(scale))
82 if (!validatePadding(padding))
85 const std::vector<const moveit::core::LinkModel*>& links =
robot_model_->getLinkModelsWithCollisionGeometry();
86 for (
const auto link : links)
95 : robot_model_(model), world_(world), world_const_(world_)
97 if (!validateScale(scale))
99 if (!validatePadding(padding))
102 const std::vector<const moveit::core::LinkModel*>& links =
robot_model_->getLinkModelsWithCollisionGeometry();
103 for (
const auto link : links)
111 : robot_model_(other.robot_model_), world_(world), world_const_(world)
118 if (!validatePadding(padding))
120 std::vector<std::string> u;
121 const std::vector<const moveit::core::LinkModel*>& links =
robot_model_->getLinkModelsWithCollisionGeometry();
122 for (
const auto link : links)
125 u.push_back(link->getName());
134 if (!validateScale(scale))
136 std::vector<std::string> u;
137 const std::vector<const moveit::core::LinkModel*>& links =
robot_model_->getLinkModelsWithCollisionGeometry();
138 for (
const auto link : links)
141 u.push_back(link->getName());
150 validatePadding(padding);
155 std::vector<std::string> u(1, link_name);
171 std::vector<std::string> u;
172 for (
const auto& link_pad_pair : padding)
174 validatePadding(link_pad_pair.second);
175 const bool update =
getLinkPadding(link_pad_pair.first) != link_pad_pair.second;
178 u.push_back(link_pad_pair.first);
191 validateScale(scale);
196 std::vector<std::string> u(1, link_name);
212 std::vector<std::string> u;
213 for (
const auto& link_scale_pair : scale)
215 const bool update =
getLinkScale(link_scale_pair.first) != link_scale_pair.second;
216 link_scale_[link_scale_pair.first] = link_scale_pair.second;
218 u.push_back(link_scale_pair.first);
231 std::vector<std::string> u;
232 for (
const auto&
p : padding)
234 validatePadding(
p.padding);
238 u.push_back(
p.link_name);
246 std::vector<std::string> u;
247 for (
const auto& s : scale)
249 validateScale(s.scale);
250 const bool update =
getLinkScale(s.link_name) != s.scale;
253 u.push_back(s.link_name);
264 moveit_msgs::msg::LinkPadding lp_msg;
265 lp_msg.link_name = lp.first;
266 lp_msg.padding = lp.second;
267 padding.push_back(lp_msg);
276 moveit_msgs::msg::LinkScale ls_msg;
277 ls_msg.link_name = ls.first;
278 ls_msg.scale = ls.second;
279 scale.push_back(ls_msg);
291 world_ = std::make_shared<World>();
293 world_const_ = world;
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Provides the interface to the individual collision checking libraries.
virtual void setWorld(const WorldPtr &world)
void getPadding(std::vector< moveit_msgs::msg::LinkPadding > &padding) const
Get the link padding as a vector of messages.
void setLinkScale(const std::string &link_name, double scale)
Set the scaling for a particular link.
void setLinkPadding(const std::string &link_name, double padding)
Set the link padding for a particular link.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const =0
Check for robot self collision. Any collision between any pair of links is checked for,...
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
void setScale(double scale)
Set the link scaling (for every link)
void setPadding(double padding)
Set the link padding (for every link)
virtual void checkCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const
Check whether the robot model is in collision with itself or the world at a particular state....
void getScale(std::vector< moveit_msgs::msg::LinkScale > &scale) const
Get the link scaling as a vector of messages.
std::map< std::string, double > link_padding_
The internally maintained map (from link names to padding)
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const =0
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
virtual void updatedPaddingOrScaling(const std::vector< std::string > &links)
When the scale or padding is changed for a set of links by any of the functions in this class,...
std::map< std::string, double > link_scale_
The internally maintained map (from link names to scaling)
Maintain a representation of the environment.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Representation of a collision checking request.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.