39#include <rclcpp/logger.hpp>
40#include <rclcpp/logging.hpp>
62 double padding,
double scale)
77 RCLCPP_INFO(getLogger(),
"Using AllValid collision detection. No collision checking is performed.");
86 RCLCPP_INFO(getLogger(),
"Using AllValid collision detection. No collision checking is performed.");
95 RCLCPP_INFO(getLogger(),
"Using AllValid collision detection. No collision checking is performed.");
105 RCLCPP_INFO(getLogger(),
"Using AllValid collision detection. No collision checking is performed.");
130 RCLCPP_INFO(getLogger(),
"Using AllValid collision detection. No collision checking is performed.");
139 RCLCPP_INFO(getLogger(),
"Using AllValid collision detection. No collision checking is performed.");
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
static const std::string NAME
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr &robot_model, double padding=0.0, double scale=1.0)
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
The distance to self-collision given the robot is at state state.
virtual double distanceRobot(const moveit::core::RobotState &state) const
Provides the interface to the individual collision checking libraries.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Representation of a collision checking request.
bool verbose
Flag indicating whether information about detected collisions should be reported.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Representation of a distance-reporting request.
Result of a distance request.
bool collision
Indicates if two objects were in collision.