Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Servo] Fix collision checking with attached objects #2747

Merged
merged 3 commits into from
Mar 19, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,9 @@ class CollisionMonitor
// Variables

const servo::Params& servo_params_;
moveit::core::RobotStatePtr robot_state_;

const planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
moveit::core::RobotState robot_state_;

// The collision monitor thread.
std::thread monitor_thread_;
Expand Down
12 changes: 8 additions & 4 deletions moveit_ros/moveit_servo/src/collision_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ CollisionMonitor::CollisionMonitor(const planning_scene_monitor::PlanningSceneMo
const servo::Params& servo_params, std::atomic<double>& collision_velocity_scale)
: servo_params_(servo_params)
, planning_scene_monitor_(planning_scene_monitor)
, robot_state_(planning_scene_monitor->getPlanningScene()->getCurrentState())
, collision_velocity_scale_(collision_velocity_scale)
{
scene_collision_request_.distance = true;
Expand Down Expand Up @@ -105,22 +106,25 @@ void CollisionMonitor::checkCollisions()
if (servo_params_.check_collisions)
{
// Fetch latest robot state.
robot_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
robot_state_ = planning_scene_monitor_->getPlanningScene()->getCurrentState();
// This must be called before doing collision checking.
robot_state_->updateCollisionBodyTransforms();
std::vector<const moveit::core::AttachedBody*> bodies;
robot_state_.getAttachedBodies(bodies);
RCLCPP_ERROR(getLogger(), "SCASTRO Servo Attached bodies: %ld", bodies.size());
sea-bass marked this conversation as resolved.
Show resolved Hide resolved
robot_state_.updateCollisionBodyTransforms();

// Get a read-only copy of planning scene.
planning_scene_monitor::LockedPlanningSceneRO locked_scene(planning_scene_monitor_);

// Check collision with environment.
scene_collision_result_.clear();
locked_scene->getCollisionEnv()->checkRobotCollision(scene_collision_request_, scene_collision_result_,
*robot_state_, locked_scene->getAllowedCollisionMatrix());
robot_state_, locked_scene->getAllowedCollisionMatrix());

// Check robot self collision.
self_collision_result_.clear();
locked_scene->getCollisionEnvUnpadded()->checkSelfCollision(
self_collision_request_, self_collision_result_, *robot_state_, locked_scene->getAllowedCollisionMatrix());
self_collision_request_, self_collision_result_, robot_state_, locked_scene->getAllowedCollisionMatrix());

// If collision detected scale velocity to 0, else start decelerating exponentially.
// velocity_scale = e ^ k * (collision_distance - threshold)
Expand Down
Loading