Environment#

class Environment
double safety_margin

Additional global safety margin used for collision checking.

Environment(std::shared_ptr<Robot> robot, float safety_margin = 0.0)
std::shared_ptr<Robot> get_robot(const std::string &name = "")

Get the robot with the given name from the environment. In case there is only a single robot in the environment, the default empty name argument will return this robot. Otherwise throws an error if no robot with the name exists.

Point get_waypoint(const std::string &name)

Get the waypoint with the given name from the environment. Returns either a Waypoint, a CartesianWaypoint, a Region, or a CartesianRegion. Throws an error if no waypoint with the name exists.

Obstacle get_obstacle(const std::string &name)

Get the obstacle with the given name from the environment. Throws an error if no obstacle with the name exists.

Obstacle *add_obstacle(const Obstacle&)

Adds an obstacle to the environment. Returns a pointer to the added obstacle for future changes.

Obstacle *add_obstacle(const Object&, const Frame &origin = Frame::Identity(), const std::string &color = "000000")

Adds a collision object to the environment at the given origin frame. Returns a pointer to the added obstacle for future changes.

Obstacle *add_obstacle(const std::string &name, const Object&, const Frame &origin = Frame::Identity(), const std::string &color = "000000")

Adds a collision object to the environment at the given origin frame. Returns a pointer to the added obstacle for future changes.

void remove_obstacle(Obstacle *obstacle)

Removes the given obstacles from the environment and from all collision checking.

void update_fixed_obstacles()

Updates all fixed obstacles for the internal collision checking. This should be called after changing e.g. the position or size of an obstacle.

void update_height_field(Obstacle *obstacle)

Updates the heights matrix of a given height field obstacle for the internal collision checking.

void update_joint_position(const std::shared_ptr<Robot> &robot, const Config &joint_position)

Updates the joint position of the given robot for the internal collision checking.

bool check_collision(const Config &joint_position)

Returns true if the given joint position is in collision with the environment, otherwise false.

bool check_collision(const std::shared_ptr<Robot> &robot, const Config &joint_position)

Returns true if the given joint position for the specific robot is in collision with the environment, otherwise false.

std::optional<Config> get_collision_free_joint_position_nearby(const Config &joint_position, const std::shared_ptr<Robot> &robot = nullptr)

Calculate a collision free joint position close to the reference position.