-
Notifications
You must be signed in to change notification settings - Fork 9
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
Planning Scene transcription V2 #31
Changes from all commits
0b10366
808ed9a
996476a
9506420
204b105
1a24acf
ecd3376
a565092
77d6f01
34598ae
59fa46b
f10ff7a
c891ed9
c215249
418a107
b4b02e8
eedf50d
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,5 +1,5 @@ | ||
services: | ||
moveit: | ||
moveit_drake: | ||
image: moveit_drake:latest | ||
container_name: moveit_drake | ||
build: | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -160,7 +160,7 @@ void KTOptPlanningContext::solve(planning_interface::MotionPlanResponse& res) | |
visualizer_->ForcedPublish(vis_context); | ||
|
||
// Without these sleeps, the visualizer won't give you time to load your browser | ||
std::this_thread::sleep_for(std::chrono::milliseconds(static_cast<int>(params_.trajectory_time_step * 1000.0))); | ||
std::this_thread::sleep_for(std::chrono::milliseconds(static_cast<int>(params_.trajectory_time_step * 10000.0))); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Are you wanting to merge with this? I had an idea which I could try -- basically have the motion planning terminate but starting the visualization separately in a thread so Meshcat doesn't die instantly, but also doesn't hold up the actual planning? Not for this PR, but at least the delay should be reduced |
||
} | ||
visualizer_->StopRecording(); | ||
visualizer_->PublishRecording(); | ||
|
@@ -228,6 +228,7 @@ void KTOptPlanningContext::setRobotDescription(std::string robot_description) | |
|
||
void KTOptPlanningContext::transcribePlanningScene(const planning_scene::PlanningScene& planning_scene) | ||
{ | ||
// Transcribe the planning scene into a drake scene graph | ||
try | ||
{ | ||
auto world = planning_scene.getWorld(); | ||
|
@@ -248,29 +249,83 @@ void KTOptPlanningContext::transcribePlanningScene(const planning_scene::Plannin | |
} | ||
if (object == OCTOMAP_NS) | ||
{ | ||
RCLCPP_ERROR(getLogger(), "skipping octomap for now ..."); | ||
RCLCPP_WARN(getLogger(), "Octomap not supported for now ... "); | ||
continue; | ||
} | ||
for (const auto& shape : collision_object->shapes_) | ||
for (int i = 0; i < collision_object->shapes_.size(); ++i) | ||
{ | ||
RCLCPP_ERROR(getLogger(), "iterating inside collision object's shapes"); | ||
const auto& pose = collision_object->shape_poses_[0]; | ||
std::string shape_name = object + std::to_string(i); | ||
const auto& shape = collision_object->shapes_[i]; | ||
const auto& pose = collision_object->pose_; | ||
const auto& shape_pose = collision_object->shape_poses_[i]; | ||
const auto& shape_type = collision_object->shapes_[i]->type; | ||
|
||
switch (shape_type) | ||
{ | ||
case shapes::ShapeType::BOX: | ||
{ | ||
const auto objectptr = std::dynamic_pointer_cast<const shapes::Box>(shape); | ||
const SourceId box_source_id = scene_graph.RegisterSource(shape_name); | ||
const GeometryId box_geom_id = scene_graph.RegisterAnchoredGeometry( | ||
box_source_id, | ||
std::make_unique<GeometryInstance>( | ||
RigidTransformd(pose), | ||
std::make_unique<Box>(objectptr->size[0], objectptr->size[1], objectptr->size[2]), shape_name)); | ||
|
||
// add illustration, proximity, perception properties | ||
scene_graph.AssignRole(box_source_id, box_geom_id, IllustrationProperties()); | ||
scene_graph.AssignRole(box_source_id, box_geom_id, ProximityProperties()); | ||
scene_graph.AssignRole(box_source_id, box_geom_id, PerceptionProperties()); | ||
break; | ||
} | ||
case shapes::ShapeType::UNKNOWN_SHAPE: | ||
{ | ||
RCLCPP_WARN(getLogger(), "Unknown shape, ignoring in scene graph"); | ||
break; | ||
} | ||
case shapes::ShapeType::SPHERE: | ||
{ | ||
const auto objectptr = std::dynamic_pointer_cast<const shapes::Sphere>(shape); | ||
const SourceId box_source_id = scene_graph.RegisterSource(shape_name); | ||
const GeometryId box_geom_id = scene_graph.RegisterAnchoredGeometry( | ||
box_source_id, std::make_unique<GeometryInstance>( | ||
RigidTransformd(pose), std::make_unique<Sphere>(objectptr->radius), shape_name)); | ||
RCLCPP_INFO(getLogger(), "Sphere"); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Remove |
||
|
||
// add illustration, proximity, perception properties | ||
scene_graph.AssignRole(box_source_id, box_geom_id, IllustrationProperties()); | ||
scene_graph.AssignRole(box_source_id, box_geom_id, ProximityProperties()); | ||
scene_graph.AssignRole(box_source_id, box_geom_id, PerceptionProperties()); | ||
break; | ||
} | ||
case shapes::ShapeType::CYLINDER: | ||
{ | ||
const auto objectptr = std::dynamic_pointer_cast<const shapes::Cylinder>(shape); | ||
const SourceId box_source_id = scene_graph.RegisterSource(shape_name); | ||
const GeometryId box_geom_id = scene_graph.RegisterAnchoredGeometry( | ||
box_source_id, | ||
std::make_unique<GeometryInstance>( | ||
RigidTransformd(pose), std::make_unique<Cylinder>(objectptr->radius, objectptr->length), shape_name)); | ||
RCLCPP_INFO(getLogger(), "Cylinder"); | ||
|
||
// add illustration, proximity, perception properties | ||
scene_graph.AssignRole(box_source_id, box_geom_id, IllustrationProperties()); | ||
scene_graph.AssignRole(box_source_id, box_geom_id, ProximityProperties()); | ||
scene_graph.AssignRole(box_source_id, box_geom_id, PerceptionProperties()); | ||
break; | ||
} | ||
case shapes::ShapeType::CONE: | ||
{ | ||
RCLCPP_WARN(getLogger(), "Cone not supported in drake"); | ||
break; | ||
} | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Are these all possible shape types? If not, you should add a default like this at the end of the switch statement
|
||
default: | ||
{ | ||
RCLCPP_WARN(getLogger(), "Shape TYPE conversation to drake is not implemented"); | ||
} | ||
} | ||
|
||
// Creates a box geometry and anchors it to the world origin. Better | ||
// approach is to create a ground object, anchor that, and then anchor | ||
// every non-moving entity to the ground plane | ||
// TODO: Create and anchor ground entity | ||
Vector3d p(0.3, -0.3, 0.5); | ||
const SourceId box_source_id = scene_graph.RegisterSource("box1"); | ||
const GeometryId box_geom_id = scene_graph.RegisterAnchoredGeometry( | ||
box_source_id, std::make_unique<GeometryInstance>( | ||
RigidTransformd(p), std::make_unique<Box>(0.15, 0.15, 0.15), | ||
"box")); // hard coded for now because I know box dimensions and pose, from | ||
|
||
// add illustration, proximity, perception properties | ||
scene_graph.AssignRole(box_source_id, box_geom_id, IllustrationProperties()); | ||
scene_graph.AssignRole(box_source_id, box_geom_id, ProximityProperties()); | ||
scene_graph.AssignRole(box_source_id, box_geom_id, PerceptionProperties()); | ||
} | ||
} | ||
} | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Similar to Sebastian's comment: Why do we need this?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I added this for linting and LSP support, so that vim has access to the symbols for functionality like Goto definition/declaration etc.