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

Planning Scene transcription V2 #31

Merged
merged 17 commits into from
Aug 20, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
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
4 changes: 3 additions & 1 deletion .docker/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ RUN apt update && \
apt install -y \
build-essential \
clang-format-14 \
clangd-12 \
Copy link
Contributor

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?

Copy link
Member Author

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.

cmake \
git-lfs \
python3-colcon-common-extensions \
Expand All @@ -36,7 +37,8 @@ RUN apt update && \
ros-dev-tools \
ros-${ROS_DISTRO}-desktop \
ros-${ROS_DISTRO}-rmw-cyclonedds-cpp \
wget
wget && \
update-alternatives --install /usr/bin/clangd clangd /usr/bin/clangd-12 100
sea-bass marked this conversation as resolved.
Show resolved Hide resolved

RUN pip3 install colcon-mixin pre-commit && \
colcon mixin add default https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml && \
Expand Down
2 changes: 1 addition & 1 deletion docker-compose.yaml
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:
Expand Down
3 changes: 3 additions & 0 deletions include/ktopt_interface/ktopt_planning_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ namespace ktopt_interface
// declare all namespaces to be used
using drake::geometry::AddRigidHydroelasticProperties;
using drake::geometry::Box;
using drake::geometry::Cylinder;
using drake::geometry::FrameId;
using drake::geometry::GeometryFrame;
using drake::geometry::GeometryId;
Expand All @@ -43,6 +44,7 @@ using drake::geometry::ProximityProperties;
using drake::geometry::Role;
using drake::geometry::SceneGraph;
using drake::geometry::SourceId;
using drake::geometry::Sphere;
using drake::math::RigidTransformd;
using drake::multibody::AddMultibodyPlantSceneGraph;
using drake::multibody::MinimumDistanceLowerBoundConstraint;
Expand All @@ -56,6 +58,7 @@ using drake::systems::Diagram;
using drake::systems::DiagramBuilder;
using drake::visualization::ApplyVisualizationConfig;
using drake::visualization::VisualizationConfig;
using Eigen::Matrix3d;
using Eigen::MatrixXd;
using Eigen::Vector3d;
using Eigen::VectorXd;
Expand Down
93 changes: 74 additions & 19 deletions src/ktopt_planning_context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)));
Copy link
Contributor

Choose a reason for hiding this comment

The 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();
Expand Down Expand Up @@ -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();
Expand All @@ -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");
Copy link
Contributor

Choose a reason for hiding this comment

The 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;
}
Copy link
Contributor

Choose a reason for hiding this comment

The 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");
}

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());
}
}
}
Expand Down
Loading