Go to the documentation of this file.
42 #include <moveit_msgs/LinkPadding.h>
43 #include <moveit_msgs/LinkScale.h>
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,
101 virtual void checkCollision(
const CollisionRequest& req, CollisionResult& res,
111 const AllowedCollisionMatrix& acm)
const;
143 const AllowedCollisionMatrix& acm)
const = 0;
161 virtual void distanceSelf(
const DistanceRequest& req, DistanceResult& res,
172 return res.minimum_distance.distance;
185 return res.minimum_distance.distance;
192 virtual void distanceRobot(
const DistanceRequest& req, DistanceResult& res,
207 return res.minimum_distance.distance;
216 bool verbose =
false)
const
232 virtual void setWorld(
const WorldPtr& world);
241 const WorldConstPtr&
getWorld()
const
250 const moveit::core::RobotModelConstPtr&
getRobotModel()
const
259 void setLinkPadding(
const std::string& link_name,
double padding);
265 void setLinkPadding(
const std::map<std::string, double>& padding);
271 void setLinkScale(
const std::string& link_name,
double scale);
274 double getLinkScale(
const std::string& link_name)
const;
277 void setLinkScale(
const std::map<std::string, double>& scale);
280 const std::map<std::string, double>&
getLinkScale()
const;
289 void setPadding(
const std::vector<moveit_msgs::LinkPadding>& padding);
292 void getPadding(std::vector<moveit_msgs::LinkPadding>& padding)
const;
295 void setScale(
const std::vector<moveit_msgs::LinkScale>& scale);
298 void getScale(std::vector<moveit_msgs::LinkScale>& scale)
const;
void getScale(std::vector< moveit_msgs::LinkScale > &scale) const
Get the link scaling as a vector of messages.
const moveit::core::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
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...
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,...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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....
bool verbose
Log debug information.
void setLinkPadding(const std::string &link_name, double padding)
Set the link padding for a particular link.
void setLinkScale(const std::string &link_name, double scale)
Set the scaling for a particular link.
Definition of a structure for the allowed collision matrix.
void setPadding(double padding)
Set the link padding (for every link)
WorldConstPtr world_const_
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
World::ObjectConstPtr ObjectConstPtr
virtual void distanceRobot(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const =0
Compute the distance between a robot and the world.
void setScale(double scale)
Set the link scaling (for every link)
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
void getPadding(std::vector< moveit_msgs::LinkPadding > &padding) const
Get the link padding as a vector of messages.
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
Result of a distance request.
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
World::ObjectPtr ObjectPtr
double distance
The distance between two objects. If two objects are in collision, distance <= 0.
virtual void setWorld(const WorldPtr &world)
Representation of a distance-reporting request.
void enableGroup(const moveit::core::RobotModelConstPtr &robot_model)
Compute active_components_only_ based on req_.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
std::map< std::string, double > link_scale_
The internally maintained map (from link names to scaling)
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()
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.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sat Dec 21 2024 03:23:41