40 #include <exotica_core/attach_link_initializer.h> 41 #include <exotica_core/box_shape_initializer.h> 42 #include <exotica_core/collision_scene_initializer.h> 43 #include <exotica_core/cylinder_shape_initializer.h> 44 #include <exotica_core/link_initializer.h> 45 #include <exotica_core/mesh_shape_initializer.h> 46 #include <exotica_core/octree_shape_initializer.h> 47 #include <exotica_core/shape_initializer.h> 48 #include <exotica_core/sphere_shape_initializer.h> 49 #include <exotica_core/trajectory_initializer.h> 51 #include <moveit/version.h> 57 Scene::Scene(
const std::string& name) : request_needs_updating_(false)
76 robot_model::RobotModelPtr model;
77 if (init.URDF ==
"" || init.SRDF ==
"")
89 if (
Server::IsRos() && init.SetRobotDescriptionRosParams && init.URDF !=
"" && init.SRDF !=
"")
92 const std::string urdf_string =
PathExists(init.URDF) ?
LoadFile(init.URDF) : init.URDF;
93 const std::string srdf_string =
PathExists(init.SRDF) ?
LoadFile(init.SRDF) : init.SRDF;
102 proxy_pub_ = Server::Advertise<visualization_msgs::Marker>(object_name_ + (object_name_ ==
"" ?
"" :
"/") +
"CollisionProxies", 1,
true);
108 if (init.LoadScene !=
"")
110 std::vector<std::string> files =
ParseList(init.LoadScene,
';');
111 for (
const std::string& file : files)
LoadSceneFile(file, Eigen::Isometry3d::Identity(),
false);
117 LinkInitializer link(linkInit);
120 Eigen::Vector4d link_color = Eigen::Vector4d::Zero();
121 if (link.Shape.size() == 1)
123 ShapeInitializer shape(link.Shape[0]);
124 link_color = shape.Color;
126 if (shape.Type ==
"Box")
128 BoxShapeInitializer box(link.Shape[0]);
129 std::cout <<
"BOX: " << box.Dimensions.transpose() << std::endl;
130 link_shape.reset(
new shapes::Box(box.Dimensions.x(), box.Dimensions.y(), box.Dimensions.z()));
132 else if (shape.Type ==
"Cylinder")
134 CylinderShapeInitializer cylinder(link.Shape[0]);
137 else if (shape.Type ==
"Mesh")
139 MeshShapeInitializer mesh(link.Shape[0]);
143 else if (shape.Type ==
"Octree")
145 OctreeShapeInitializer octree(link.Shape[0]);
148 else if (shape.Type ==
"Sphere")
150 SphereShapeInitializer sphere(link.Shape[0]);
155 ThrowPretty(
"Unrecognized ShapeType: " << shape.Type);
158 else if (link.Shape.size() > 1)
160 ThrowPretty(
"Only one Shape per Link allowed, given: " << link.Shape.size());
167 if (init.RobotLinksToExcludeFromCollisionScene.size() > 0)
169 for (
const auto& link : init.RobotLinksToExcludeFromCollisionScene)
177 if (init.WorldLinksToExcludeFromCollisionScene.size() > 0)
179 for (
const auto& link : init.WorldLinksToExcludeFromCollisionScene)
188 if (!init.DoNotInstantiateCollisionScene)
190 if (init.CollisionScene.size() == 0)
195 else if (init.CollisionScene.size() == 1)
202 ThrowPretty(
"Only one CollisionScene per scene allowed - " << init.CollisionScene.size() <<
" provided");
218 AttachLinkInitializer link(linkInit);
231 std::vector<std::string> acm_names;
232 ps_->getAllowedCollisionMatrix().getAllEntryNames(acm_names);
233 for (
auto& name1 : acm_names)
235 for (
auto& name2 : acm_names)
238 ps_->getAllowedCollisionMatrix().getAllowedCollision(name1, name2, type);
239 if (type == collision_detection::AllowedCollision::Type::ALWAYS)
250 TrajectoryInitializer trajInit(it);
251 if (trajInit.File !=
"")
262 if (init.DynamicsSolver.size() > 0)
265 if (init.DynamicsSolver.size() > 1)
ThrowPretty(
"Only one DynamicsSolver per scene allowed - " << init.DynamicsSolver.size() <<
" provided");
307 it.second.first.lock()->generated_offset = it.second.second->GetPosition(t);
327 for (
const auto& joint : modelState)
331 ps_->getCurrentStateNonConst().setVariablePosition(joint.first, joint.second);
333 catch (
const std::out_of_range& e)
335 HIGHLIGHT(
"Could not find Kinematica joint name in MoveIt: " + joint.first);
347 Eigen::Quaterniond quat(Eigen::Map<const Eigen::Matrix3d>(rot.
data).transpose());
371 visualization_msgs::Marker
Scene::ProxyToMarker(
const std::vector<CollisionProxy>& proxies,
const std::string& frame)
373 visualization_msgs::Marker ret;
374 ret.header.frame_id =
"exotica/" + frame;
375 ret.action = visualization_msgs::Marker::ADD;
376 ret.frame_locked =
false;
380 ret.type = visualization_msgs::Marker::LINE_LIST;
381 ret.points.resize(proxies.size() * 6);
382 ret.colors.resize(proxies.size() * 6);
384 ret.pose.orientation.w = 1.0;
385 double normalLength = 0.01;
386 std_msgs::ColorRGBA normal =
GetColor(0.8, 0.8, 0.8);
387 std_msgs::ColorRGBA far =
GetColor(0.5, 0.5, 0.5);
388 std_msgs::ColorRGBA colliding =
GetColor(1, 0, 0);
389 for (
int i = 0; i < proxies.size(); ++i)
401 ret.colors[i * 6] = ret.colors[i * 6 + 1] = proxies[i].distance > 0 ? far : colliding;
402 ret.colors[i * 6 + 2] = ret.colors[i * 6 + 3] = ret.colors[i * 6 + 4] = ret.colors[i * 6 + 5] = normal;
409 ps_->usePlanningSceneMsg(scene);
416 ps_->processPlanningSceneWorldMsg(*world);
454 moveit_msgs::PlanningScene msg;
455 ps_->getPlanningSceneMsg(msg);
460 msg.link_padding.clear();
461 msg.link_scale.clear();
462 for (
auto robot_link : msg.robot_state.joint_state.name)
464 moveit_msgs::LinkPadding padding;
465 padding.link_name = robot_link;
467 msg.link_padding.push_back(padding);
469 moveit_msgs::LinkScale scale;
470 scale.link_name = robot_link;
472 msg.link_scale.push_back(scale);
480 for (
auto it : msg.world.collision_objects)
483 for (
auto primitive : it.primitives)
489 primitive = boost::get<shape_msgs::SolidPrimitive>(tmp_msg);
493 for (
auto mesh : it.meshes)
499 mesh = boost::get<shape_msgs::Mesh>(tmp_msg);
586 Eigen::Isometry3d tmp_offset;
588 LoadScene(scene, tmp_offset, update_collision_scene);
593 std::stringstream ss(scene);
599 Eigen::Isometry3d tmp_offset;
601 LoadSceneFile(file_name, tmp_offset, update_collision_scene);
613 #if ROS_VERSION_MINIMUM(1, 14, 0) // if ROS version >= ROS_MELODIC 614 ps_->loadGeometryFromStream(in, offset);
616 ps_->loadGeometryFromStream(in, Eigen::Affine3d(offset));
625 std::stringstream ss;
626 ps_->saveGeometryToStream(ss);
633 ps_->removeAllCollisionObjects();
642 Eigen::Isometry3d pose;
644 std::string shape_resource_path = it->shape_resource_path;
645 Eigen::Vector3d scale = it->scale;
646 it =
kinematica_.
AddElement(it->segment.getName(), pose, it->parent_name, it->shape, it->segment.getInertia(), it->color, it->visual, it->is_controlled);
647 it->shape_resource_path = shape_resource_path;
653 for (
auto& traj : trajectory_generators_copy)
681 std::map<std::string, int> visual_map;
682 for (
const auto&
object : *
ps_->getWorld())
684 if (
object.second->shapes_.size())
687 Eigen::Isometry3d obj_transform;
688 obj_transform.translation() =
object.second->shape_poses_[0].translation();
689 obj_transform.linear() =
object.second->shape_poses_[0].rotation();
691 std::vector<VisualElement> visuals;
692 for (
int i = 0; i <
object.second->shape_poses_.size(); ++i)
694 Eigen::Isometry3d shape_transform;
695 shape_transform.translation() =
object.second->shape_poses_[i].translation();
696 shape_transform.linear() =
object.second->shape_poses_[i].rotation();
697 Eigen::Isometry3d trans = obj_transform.inverse() * shape_transform;
699 std::string name =
object.first;
701 const auto& it = visual_map.find(name);
702 if (it != visual_map.end())
705 name = name +
"_" + std::to_string(it->second);
709 visual_map[name] = 0;
714 if (
ps_->hasObjectColor(
object.first))
716 auto color_msg =
ps_->getObjectColor(
object.first);
717 visual.
color = Eigen::Vector4d(color_msg.r, color_msg.g, color_msg.b, color_msg.a);
724 if (visual.
shape) visuals.push_back(visual);
726 element->visual = visuals;
730 HIGHLIGHT(
"Object with no shapes ('" <<
object.first <<
"')");
735 ps_->getCurrentStateNonConst().update(
true);
736 #if MOVEIT_VERSION_MAJOR >= 1 && MOVEIT_VERSION_MINOR >= 1 737 const std::vector<const robot_model::LinkModel*>& links =
ps_->getCollisionEnv()->getRobotModel()->getLinkModelsWithCollisionGeometry();
739 const std::vector<const robot_model::LinkModel*>& links =
ps_->getCollisionRobot()->getRobotModel()->getLinkModelsWithCollisionGeometry();
742 int last_controlled_joint_id = -1;
743 std::string last_controlled_joint_name =
"";
747 for (
int i = 0; i < links.size(); ++i)
755 Eigen::Isometry3d obj_transform;
756 obj_transform.translation() =
ps_->getCurrentState().getGlobalLinkTransform(links[i]).translation();
757 obj_transform.linear() =
ps_->getCurrentState().getGlobalLinkTransform(links[i]).rotation();
762 if (last_controlled_joint_id != joint_id)
765 last_controlled_joint_id = joint_id;
769 for (
int j = 0; j < links[i]->getShapes().size(); ++j)
778 Eigen::Affine3d collisionBodyTransform_affine =
ps_->getCurrentState().getCollisionBodyTransform(links[i], j);
779 Eigen::Isometry3d collisionBodyTransform;
780 collisionBodyTransform.translation() = collisionBodyTransform_affine.translation();
781 collisionBodyTransform.linear() = collisionBodyTransform_affine.rotation();
782 Eigen::Isometry3d trans = obj_transform.inverse(Eigen::Isometry) * collisionBodyTransform;
784 std::string collision_element_name = links[i]->getName() +
"_collision_" + std::to_string(j);
785 std::shared_ptr<KinematicElement> element =
kinematica_.
AddElement(collision_element_name, trans, links[i]->
getName(), links[i]->getShapes()[j]);
791 if (last_controlled_joint_name !=
"")
808 Eigen::Isometry3d pose;
814 void Scene::AddObject(
const std::string& name,
const KDL::Frame& transform,
const std::string& parent,
const std::string& shape_resource_path,
const Eigen::Vector3d& scale,
const KDL::RigidBodyInertia& inertia,
const Eigen::Vector4d& color,
bool update_collision_scene)
819 Eigen::Isometry3d pose;
831 throw std::runtime_error(
"link '" + name +
"' already exists in kinematic tree");
833 Eigen::Isometry3d pose;
835 ps_->getWorldNonConst()->addToObject(name, shape, pose);
846 if ((*it)->segment.getName() == name)
858 ThrowPretty(
"Link " << name <<
" not removed as it cannot be found.");
904 const auto& it = tree.find(link);
905 if (it == tree.end())
ThrowPretty(
"Can't find link '" << link <<
"'!");
906 if (traj->GetDuration() == 0.0)
ThrowPretty(
"The trajectory is empty!");
907 trajectory_generators_[link] = std::pair<std::weak_ptr<KinematicElement>, std::shared_ptr<Trajectory>>(it->second, traj);
908 it->second.lock()->is_trajectory_generated =
true;
915 return it->second.second;
922 it->second.first.lock()->is_trajectory_generated =
false;
bool PathExists(const std::string &path)
void AddTrajectory(const std::string &link, const std::string &traj)
void LoadSceneFromStringStream(std::istream &in, const Eigen::Isometry3d &offset, bool update_collision_scene)
void UpdateCollisionObjects()
planning_scene::PlanningScenePtr ps_
Internal MoveIt planning scene.
std::map< std::string, double > GetModelStateMap() const
std::vector< std::string > GetControlledJointNames()
static std::shared_ptr< exotica::CollisionScene > CreateCollisionScene(const std::string &type, bool prepend=true)
bool DoesLinkWithNameExist(std::string name) const
Checks whether a link with this name exists in any of the trees.
bool get_has_quaternion_floating_base() const
void Update(Eigen::VectorXdRefConst x)
void publish(const boost::shared_ptr< M > &message) const
const std::vector< std::string > & GetControlledLinkNames() const
void LoadSceneFile(const std::string &file_name, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
std::vector< std::string > GetModelJointNames()
std::string GetRootFrameName()
void UpdateMoveItPlanningScene()
Updates the internal state of the MoveIt PlanningScene from Kinematica.
void PublishProxies(const std::vector< CollisionProxy > &proxies)
BaseType GetModelBaseType() const
void InstantiateObject(const Initializer &init)
void SetModelState(Eigen::VectorXdRefConst x, double t=0, bool update_traj=true)
int get_num_positions() const
std::string getName(void *handle)
int get_num_state() const
std::vector< std::string > ParseList(const std::string &value, char token= ',')
std::shared_ptr< DynamicsSolver > GetDynamicsSolver() const
Returns a pointer to the CollisionScene.
std::vector< std::shared_ptr< KinematicElement > > custom_links_
List of frames/links added on top of robot links and scene objects defined in the MoveIt scene...
void AddTrajectoryFromFile(const std::string &link, const std::string &traj)
void AddObject(const std::string &name, const KDL::Frame &transform=KDL::Frame(), const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const bool update_collision_scene=true)
void LoadScene(const std::string &scene, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
std_msgs::ColorRGBA GetColor(double r, double g, double b, double a=1.0)
std::string LoadFile(const std::string &path)
void RemoveObject(const std::string &name)
visualization_msgs::Marker ProxyToMarker(const std::vector< CollisionProxy > &proxies, const std::string &frame)
std::shared_ptr< Shape > ShapePtr
const std::vector< std::string > & GetModelLinkNames() const
void transformEigenToKDL(const Eigen::Affine3d &e, KDL::Frame &k)
const std::string & GetRootJointName() const
static std::shared_ptr< Server > Instance()
Get the server.
exotica::KinematicTree kinematica_
The kinematica tree.
Eigen::VectorXd GetModelState() const
std::shared_ptr< KinematicElement > AddEnvironmentElement(const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
int num_state_derivative_
"ndx"
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetTreeMap() const
void UpdatePlanningSceneWorld(const moveit_msgs::PlanningSceneWorldConstPtr &world)
Update the collision scene from a moveit_msgs::PlanningSceneWorld.
void Instantiate(const std::string &joint_group, robot_model::RobotModelPtr model, const std::string &name)
int GetNumModelJoints() const
std::set< std::string > robot_links_to_exclude_from_collision_scene_
List of robot links to be excluded from the collision scene.
std::shared_ptr< KinematicResponse > kinematic_solution_
std::set< std::string > world_links_to_exclude_from_collision_scene_
List of world links to be excluded from the collision scene.
Eigen::VectorXd GetControlledState() const
std::string GetRootJointName()
void Update(Eigen::VectorXdRefConst x, double t=0)
static Rotation RPY(double roll, double pitch, double yaw)
std::shared_ptr< DynamicsSolver > dynamics_solver_
The dynamics solver.
Eigen::VectorXd GetModelState()
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetCollisionTreeMap() const
const std::vector< std::string > & GetModelJointNames() const
ros::Publisher proxy_pub_
const std::string & GetRootFrameName() const
int IsControlledLink(const std::string &link_name)
bool HasModelLink(const std::string &link) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string name
void DetachObject(const std::string &name)
Detaches an object and leaves it a at its current world location. This effectively attaches the objec...
moveit_msgs::PlanningScene GetPlanningSceneMsg()
Returns the current robot configuration and collision environment as a moveit_msgs::PlanningScene.
std::map< std::string, double > GetModelStateMap()
std::shared_ptr< Trajectory > GetTrajectory(const std::string &link)
void setEntry(const std::string &name1, const std::string &name2)
static RigidBodyInertia Zero()
void AttachObjectLocal(const std::string &name, const std::string &parent, const KDL::Frame &pose)
Attaches existing object to a new parent specifying an offset in the new parent local frame...
virtual std::string type() const
Type Information wrapper: must be virtual so that it is polymorphic...
const CollisionScenePtr & GetCollisionScene() const
Returns a pointer to the CollisionScene.
SceneInitializer parameters_
void AttachObject(const std::string &name, const std::string &parent)
Attaches existing object to a new parent. E.g. attaching a grasping target to the end-effector...
Shape * constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
static std::shared_ptr< exotica::DynamicsSolver > CreateDynamicsSolver(const std::string &type, bool prepend=true)
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
int GetNumControlledJoints() const
void ChangeParent(const std::string &name, const std::string &parent, const KDL::Frame &pose, bool relative)
std::map< std::string, std::vector< std::string > > controlled_joint_to_collision_link_map_
Mapping between controlled joint name and collision links.
const std::string & GetName() const
ros::Publisher ps_pub_
Visual debug.
KinematicsRequest kinematic_request_
static void SetParam(const std::string &name, T ¶m)
void UpdatePlanningScene(const moveit_msgs::PlanningScene &scene)
Update the collision scene from a moveit_msgs::PlanningScene.
CollisionScenePtr collision_scene_
The collision scene.
#define INFO_NAMED(name, x)
int get_num_state_derivative() const
const std::vector< std::string > & GetControlledJointNames() const
std::vector< std::string > GetModelLinkNames()
std::string ParsePath(const std::string &path)
std::vector< std::string > GetControlledLinkNames()
bool constructMsgFromShape(const Shape *shape, ShapeMsg &shape_msg)
Mesh * createMeshFromResource(const std::string &resource)
#define HIGHLIGHT_NAMED(name, x)
std::map< std::string, std::weak_ptr< KinematicElement > > GetTreeMap()
std::map< std::string, AttachedObject > attached_objects_
List of attached objects These objects will be reattached if the scene gets reloaded.
exotica::KinematicTree & GetKinematicTree()
std::shared_ptr< CollisionScene > CollisionScenePtr
void UpdateSceneFrames()
Updates exotica scene object frames from the MoveIt scene.
void pointKDLToMsg(const KDL::Vector &k, geometry_msgs::Point &m)
std::map< std::string, std::pair< std::weak_ptr< KinematicElement >, std::shared_ptr< Trajectory > > > trajectory_generators_
std::function< void(std::shared_ptr< KinematicResponse >)> kinematic_request_callback_
std::shared_ptr< shapes::Shape > LoadOctreeAsShape(const std::string &file_path)
std::map< std::string, std::vector< std::string > > model_link_to_collision_link_map_
Mapping between model link names and collision links.
Eigen::VectorXd GetControlledState()
void transformKDLToEigen(const KDL::Frame &k, Eigen::Affine3d &e)
int get_num_controls() const
std::shared_ptr< KinematicElement > AddElement(const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
bool request_needs_updating_
void RequestKinematics(KinematicsRequest &request, std::function< void(std::shared_ptr< KinematicResponse >)> callback)
std::shared_ptr< KinematicResponse > RequestFrames(const KinematicsRequest &request)
KDL::Frame GetFrame(Eigen::VectorXdRefConst val)
void UpdateInternalFrames(bool update_request=true)
std::map< std::string, std::vector< std::shared_ptr< KinematicElement > > > model_link_to_collision_element_map_
bool HasAttachedObject(const std::string &name)
void RemoveTrajectory(const std::string &link)
void SetModelState(Eigen::VectorXdRefConst x)
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
void AddObjectToEnvironment(const std::string &name, const KDL::Frame &transform=KDL::Frame(), shapes::ShapeConstPtr shape=nullptr, const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const bool update_collision_scene=true)
void UpdateTrajectoryGenerators(double t=0)
bool has_quaternion_floating_base_
Whether the state includes a SE(3) floating base.
virtual void Instantiate(const SceneInitializer &init)
std::shared_ptr< const Shape > ShapeConstPtr
int get_num_velocities() const