42#include <moveit_msgs/msg/link_padding.hpp>
43#include <moveit_msgs/msg/link_scale.hpp>
61 CollisionEnv(
const moveit::core::RobotModelConstPtr& model,
double padding = 0.0,
double scale = 1.0);
68 CollisionEnv(
const moveit::core::RobotModelConstPtr& model,
const WorldPtr& world,
double padding = 0.0,
221 bool verbose =
false)
const
237 virtual void setWorld(
const WorldPtr& world);
264 void setLinkPadding(
const std::string& link_name,
double padding);
270 void setLinkPadding(
const std::map<std::string, double>& padding);
276 void setLinkScale(
const std::string& link_name,
double scale);
279 double getLinkScale(
const std::string& link_name)
const;
282 void setLinkScale(
const std::map<std::string, double>& scale);
285 const std::map<std::string, double>&
getLinkScale()
const;
294 void setPadding(
const std::vector<moveit_msgs::msg::LinkPadding>& padding);
297 void getPadding(std::vector<moveit_msgs::msg::LinkPadding>& padding)
const;
300 void setScale(
const std::vector<moveit_msgs::msg::LinkScale>& scale);
303 void getScale(std::vector<moveit_msgs::msg::LinkScale>& scale)
const;
325 WorldConstPtr world_const_;
#define MOVEIT_CLASS_FORWARD(C)
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 checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const =0
Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into...
double distanceRobot(const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const
Compute the shortest distance between a robot and the world.
virtual void setWorld(const WorldPtr &world)
const WorldConstPtr & getWorld() const
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix &acm) const =0
Check whether the robot model is in collision with the world in a continuous manner (between two robo...
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.
double distanceRobot(const moveit::core::RobotState &state, bool verbose=false) const
Compute the shortest distance between a robot and the world.
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2) const =0
Check whether the robot model is in collision with the world in a continuous manner (between two robo...
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 moveit::core::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
virtual void distanceSelf(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const =0
The distance to self-collision given the robot is at state state.
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
double distanceSelf(const moveit::core::RobotState &state) const
The distance to self-collision given the robot is at state state.
void setScale(double scale)
Set the link scaling (for every link)
void setPadding(double padding)
Set the link padding (for every link)
virtual void distanceRobot(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const =0
Compute the distance between a robot and the world.
World::ObjectPtr ObjectPtr
double distanceSelf(const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const
The distance to self-collision given the robot is at state state, ignoring the distances between 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.
World::ObjectConstPtr ObjectConstPtr
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,...
const WorldPtr & getWorld()
std::map< std::string, double > link_scale_
The internally maintained map (from link names to scaling)
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const =0
Check whether the robot model is in collision with the world. Allowed collisions are ignored....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Representation of a collision checking request.
Representation of a collision checking result.
Representation of a distance-reporting request.
void enableGroup(const moveit::core::RobotModelConstPtr &robot_model)
bool verbose
Log debug information.
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
Result of a distance request.
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
double distance
The distance between two objects. If two objects are in collision, distance <= 0.