37 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_ROBOT_ 38 #define MOVEIT_COLLISION_DETECTION_COLLISION_ROBOT_ 43 #include <moveit_msgs/LinkPadding.h> 44 #include <moveit_msgs/LinkScale.h> 62 CollisionRobot(
const robot_model::RobotModelConstPtr& model,
double padding = 0.0,
double scale = 1.0);
252 void setLinkPadding(
const std::string& link_name,
double padding);
258 void setLinkPadding(
const std::map<std::string, double>& padding);
264 void setLinkScale(
const std::string& link_name,
double scale);
267 double getLinkScale(
const std::string& link_name)
const;
270 void setLinkScale(
const std::map<std::string, double>& scale);
273 const std::map<std::string, double>&
getLinkScale()
const;
282 void setPadding(
const std::vector<moveit_msgs::LinkPadding>& padding);
285 void getPadding(std::vector<moveit_msgs::LinkPadding>& padding)
const;
288 void setScale(
const std::vector<moveit_msgs::LinkScale>& scale);
291 void getScale(std::vector<moveit_msgs::LinkScale>& scale)
const;
void setScale(double scale)
Set the link scaling (for every link)
Representation of a collision checking request.
double distanceOther(const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
The distance to another robot instance.
std::map< std::string, double > link_scale_
The internally maintained map (from link names to scaling)
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const =0
Check for self collision. Any collision between any pair of links is checked for, NO collisions are i...
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
void setPadding(double padding)
Set the link padding (for every link)
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
virtual ~CollisionRobot()
Representation of a collision checking result.
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
double distanceOther(const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const
The distance to another robot instance, ignoring distances between links that are allowed to always c...
const robot_model::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
CollisionRobot(const robot_model::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
Constructor.
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...
Generic interface to collision detection.
void enableGroup(const robot_model::RobotModelConstPtr &kmodel)
Compute active_components_only_ based on req_.
void getScale(std::vector< moveit_msgs::LinkScale > &scale) const
Get the link scaling as a vector of messages.
robot_model::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
void getPadding(std::vector< moveit_msgs::LinkPadding > &padding) const
Get the link padding as a vector of messages.
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void setLinkScale(const std::string &link_name, double scale)
Set the scaling for a particular link.
This class represents a collision model of the robot and can be used for self collision checks (to ch...
std::map< std::string, double > link_padding_
The internally maintained map (from link names to padding)
double distanceSelf(const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
The distance to self-collision given the robot is at state state, ignoring the distances between link...
double distance
The distance between two objects. If two objects are in collision, distance <= 0. ...
virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const =0
Check for collision with a different robot (possibly a different kinematic model as well)...
void setLinkPadding(const std::string &link_name, double padding)
Set the link padding for a particular link.
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
double distanceSelf(const robot_state::RobotState &state) const
The distance to self-collision given the robot is at state state.