Exotica
scene.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #ifndef EXOTICA_CORE_SCENE_H_
31 #define EXOTICA_CORE_SCENE_H_
32 
33 #include <fstream>
34 #include <functional>
35 #include <iostream>
36 #include <string>
37 
38 #include <geometric_shapes/shapes.h>
39 #include <moveit/planning_scene/planning_scene.h>
40 #include <moveit_msgs/PlanningScene.h>
41 
44 #include <exotica_core/object.h>
45 #include <exotica_core/property.h>
48 
49 #include <exotica_core/scene_initializer.h>
50 
51 namespace exotica
52 {
54 {
55  AttachedObject() = default;
56  AttachedObject(std::string _parent) : parent(_parent) {}
57  AttachedObject(std::string _parent, KDL::Frame _pose) : parent(_parent), pose(_pose) {}
58  std::string parent = "";
59  KDL::Frame pose;
60 };
61 
62 #ifndef EXOTICA_CORE_DYNAMICS_SOLVER_H_
63 template <typename T, int NX, int NU>
66 #endif
67 
69 class Scene : public Object, Uncopyable, public Instantiable<SceneInitializer>, public std::enable_shared_from_this<Scene>
70 {
71 public:
72  Scene(const std::string& name);
73  Scene();
74  virtual ~Scene();
75  virtual void Instantiate(const SceneInitializer& init);
76  void RequestKinematics(KinematicsRequest& request, std::function<void(std::shared_ptr<KinematicResponse>)> callback);
77  const std::string& GetName() const; // Deprecated - use GetObjectName
78  void Update(Eigen::VectorXdRefConst x, double t = 0);
79 
81  const CollisionScenePtr& GetCollisionScene() const;
82 
84  std::shared_ptr<DynamicsSolver> GetDynamicsSolver() const;
85 
86  std::string GetRootFrameName();
87  std::string GetRootJointName();
88 
90  std::vector<std::string> GetControlledJointNames();
91  std::vector<std::string> GetModelJointNames();
92  std::vector<std::string> GetControlledLinkNames();
93  std::vector<std::string> GetModelLinkNames();
94  Eigen::VectorXd GetControlledState();
95  Eigen::VectorXd GetModelState();
96  std::map<std::string, double> GetModelStateMap();
97  std::map<std::string, std::weak_ptr<KinematicElement>> GetTreeMap();
98  void SetModelState(Eigen::VectorXdRefConst x, double t = 0, bool update_traj = true);
99  void SetModelState(const std::map<std::string, double>& x, double t = 0, bool update_traj = true);
100 
101  void AddTrajectoryFromFile(const std::string& link, const std::string& traj);
102  void AddTrajectory(const std::string& link, const std::string& traj);
103  void AddTrajectory(const std::string& link, std::shared_ptr<Trajectory> traj);
104  std::shared_ptr<Trajectory> GetTrajectory(const std::string& link);
105  void RemoveTrajectory(const std::string& link);
106 
108  void UpdateSceneFrames();
114  void AttachObject(const std::string& name, const std::string& parent);
121  void AttachObjectLocal(const std::string& name, const std::string& parent, const KDL::Frame& pose);
122  void AttachObjectLocal(const std::string& name, const std::string& parent, const Eigen::VectorXd& pose);
127  void DetachObject(const std::string& name);
128  bool HasAttachedObject(const std::string& name);
129 
130  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);
131 
132  void AddObject(const std::string& name, const KDL::Frame& transform = KDL::Frame(), const std::string& parent = "", const std::string& shape_resource_path = "", const Eigen::Vector3d& scale = Eigen::Vector3d::Ones(), 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);
133 
134  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);
135 
136  void RemoveObject(const std::string& name);
137 
140  void UpdatePlanningSceneWorld(const moveit_msgs::PlanningSceneWorldConstPtr& world);
141 
144  void UpdatePlanningScene(const moveit_msgs::PlanningScene& scene);
145 
148  moveit_msgs::PlanningScene GetPlanningSceneMsg();
149 
150  void UpdateCollisionObjects();
151  void UpdateTrajectoryGenerators(double t = 0);
152 
153  void PublishScene();
154  void PublishProxies(const std::vector<CollisionProxy>& proxies);
155  visualization_msgs::Marker ProxyToMarker(const std::vector<CollisionProxy>& proxies, const std::string& frame);
156  void LoadScene(const std::string& scene, const Eigen::Isometry3d& offset = Eigen::Isometry3d::Identity(), bool update_collision_scene = true);
157  void LoadScene(const std::string& scene, const KDL::Frame& offset = KDL::Frame(), bool update_collision_scene = true);
158  void LoadSceneFile(const std::string& file_name, const Eigen::Isometry3d& offset = Eigen::Isometry3d::Identity(), bool update_collision_scene = true);
159  void LoadSceneFile(const std::string& file_name, const KDL::Frame& offset = KDL::Frame(), bool update_collision_scene = true);
160  std::string GetScene();
161  void CleanScene();
162 
168  const std::map<std::string, std::vector<std::string>>& GetModelLinkToCollisionLinkMap() const { return model_link_to_collision_link_map_; };
171  const std::map<std::string, std::vector<std::shared_ptr<KinematicElement>>>& GetModelLinkToCollisionElementMap() const { return model_link_to_collision_element_map_; };
174  const std::map<std::string, std::vector<std::string>>& GetControlledJointToCollisionLinkMap() const { return controlled_joint_to_collision_link_map_; };
177  int get_num_positions() const;
178  int get_num_velocities() const;
179  int get_num_controls() const;
180  int get_num_state() const;
181  int get_num_state_derivative() const;
183 
184 private:
186 
187  void UpdateInternalFrames(bool update_request = true);
188 
191 
192  void LoadSceneFromStringStream(std::istream& in, const Eigen::Isometry3d& offset, bool update_collision_scene);
193 
196 
199 
201  std::shared_ptr<DynamicsSolver> dynamics_solver_ = std::shared_ptr<DynamicsSolver>(nullptr);
202 
203  int num_positions_ = 0;
204  int num_velocities_ = 0;
205  int num_controls_ = 0;
206  int num_state_ = 0;
208 
210  planning_scene::PlanningScenePtr ps_;
211 
213  ros::Publisher ps_pub_;
214  ros::Publisher proxy_pub_;
215 
218  std::map<std::string, AttachedObject> attached_objects_;
219 
221  std::vector<std::shared_ptr<KinematicElement>> custom_links_;
222 
223  std::map<std::string, std::pair<std::weak_ptr<KinematicElement>, std::shared_ptr<Trajectory>>> trajectory_generators_;
224 
226 
228  std::map<std::string, std::vector<std::string>> model_link_to_collision_link_map_;
229  std::map<std::string, std::vector<std::shared_ptr<KinematicElement>>> model_link_to_collision_element_map_;
230 
232  std::map<std::string, std::vector<std::string>> controlled_joint_to_collision_link_map_;
233 
236 
239 
241  std::shared_ptr<KinematicResponse> kinematic_solution_;
242  std::function<void(std::shared_ptr<KinematicResponse>)> kinematic_request_callback_;
244 };
245 
246 typedef std::shared_ptr<Scene> ScenePtr;
247 } // namespace exotica
248 
249 #endif // EXOTICA_CORE_SCENE_H_
exotica::Scene::world_links_to_exclude_from_collision_scene_
std::set< std::string > world_links_to_exclude_from_collision_scene_
List of world links to be excluded from the collision scene.
Definition: scene.h:238
exotica::Scene::robot_links_to_exclude_from_collision_scene_
std::set< std::string > robot_links_to_exclude_from_collision_scene_
List of robot links to be excluded from the collision scene.
Definition: scene.h:235
exotica::Scene::GetModelJointNames
std::vector< std::string > GetModelJointNames()
exotica::AttachedObject::AttachedObject
AttachedObject(std::string _parent, KDL::Frame _pose)
Definition: scene.h:57
exotica::Scene::GetRootJointName
std::string GetRootJointName()
exotica::Scene::Update
void Update(Eigen::VectorXdRefConst x, double t=0)
exotica::Scene::DetachObject
void DetachObject(const std::string &name)
Detaches an object and leaves it a at its current world location. This effectively attaches the objec...
exotica::Scene::num_controls_
int num_controls_
"nu"
Definition: scene.h:205
trajectory.h
exotica::Scene::get_num_positions
int get_num_positions() const
exotica::AbstractDynamicsSolver
Definition: dynamics_solver.h:55
exotica::Scene::GetModelState
Eigen::VectorXd GetModelState()
exotica::Uncopyable
Definition: uncopyable.h:35
exotica::Scene::get_num_state_derivative
int get_num_state_derivative() const
exotica::Scene::proxy_pub_
ros::Publisher proxy_pub_
Definition: scene.h:214
exotica::Scene::AttachObject
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....
exotica::AttachedObject
Definition: scene.h:53
exotica::Scene::controlled_joint_to_collision_link_map_
std::map< std::string, std::vector< std::string > > controlled_joint_to_collision_link_map_
Mapping between controlled joint name and collision links.
Definition: scene.h:232
exotica::AttachedObject::parent
std::string parent
Definition: scene.h:58
exotica::Scene::ps_pub_
ros::Publisher ps_pub_
Visual debug.
Definition: scene.h:213
exotica::Scene::GetPlanningSceneMsg
moveit_msgs::PlanningScene GetPlanningSceneMsg()
Returns the current robot configuration and collision environment as a moveit_msgs::PlanningScene.
exotica::AttachedObject::AttachedObject
AttachedObject()=default
exotica::Scene
The class of EXOTica Scene.
Definition: scene.h:69
exotica::Scene::UpdatePlanningScene
void UpdatePlanningScene(const moveit_msgs::PlanningScene &scene)
Update the collision scene from a moveit_msgs::PlanningScene.
exotica::Scene::GetTrajectory
std::shared_ptr< Trajectory > GetTrajectory(const std::string &link)
exotica::Scene::get_has_quaternion_floating_base
bool get_has_quaternion_floating_base() const
property.h
exotica::Scene::AttachObjectLocal
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.
exotica::Scene::UpdateSceneFrames
void UpdateSceneFrames()
Updates exotica scene object frames from the MoveIt scene.
exotica::Scene::kinematic_request_
KinematicsRequest kinematic_request_
Definition: scene.h:240
exotica::Scene::collision_scene_
CollisionScenePtr collision_scene_
The collision scene.
Definition: scene.h:198
exotica::Scene::num_positions_
int num_positions_
"nq"
Definition: scene.h:203
exotica::Scene::trajectory_generators_
std::map< std::string, std::pair< std::weak_ptr< KinematicElement >, std::shared_ptr< Trajectory > > > trajectory_generators_
Definition: scene.h:223
exotica::Scene::model_link_to_collision_link_map_
std::map< std::string, std::vector< std::string > > model_link_to_collision_link_map_
Mapping between model link names and collision links.
Definition: scene.h:228
exotica::Scene::AlwaysUpdatesCollisionScene
bool AlwaysUpdatesCollisionScene() const
Whether the collision scene transforms get updated on every scene update.
Definition: scene.h:165
exotica::Scene::~Scene
virtual ~Scene()
exotica::Instantiable
Definition: property.h:110
exotica::Scene::num_state_
int num_state_
"nx"
Definition: scene.h:206
exotica::Scene::GetName
const std::string & GetName() const
exotica::Scene::attached_objects_
std::map< std::string, AttachedObject > attached_objects_
List of attached objects These objects will be reattached if the scene gets reloaded.
Definition: scene.h:218
exotica
Definition: cartpole_dynamics_solver.h:38
exotica::Scene::GetKinematicTree
exotica::KinematicTree & GetKinematicTree()
conversions.h
exotica::Scene::request_needs_updating_
bool request_needs_updating_
Definition: scene.h:243
exotica::Scene::kinematic_request_callback_
std::function< void(std::shared_ptr< KinematicResponse >)> kinematic_request_callback_
Definition: scene.h:242
exotica::Scene::UpdateInternalFrames
void UpdateInternalFrames(bool update_request=true)
collision_scene.h
exotica::Scene::GetControlledState
Eigen::VectorXd GetControlledState()
exotica::Scene::get_num_state
int get_num_state() const
exotica::Scene::model_link_to_collision_element_map_
std::map< std::string, std::vector< std::shared_ptr< KinematicElement > > > model_link_to_collision_element_map_
Definition: scene.h:229
exotica::Scene::HasAttachedObject
bool HasAttachedObject(const std::string &name)
exotica::Scene::RemoveTrajectory
void RemoveTrajectory(const std::string &link)
exotica::Scene::AddObjectToEnvironment
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)
exotica::Scene::RequestKinematics
void RequestKinematics(KinematicsRequest &request, std::function< void(std::shared_ptr< KinematicResponse >)> callback)
exotica::ScenePtr
std::shared_ptr< Scene > ScenePtr
Definition: scene.h:246
exotica::Object
Definition: object.h:44
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
exotica::Scene::num_velocities_
int num_velocities_
"nv"
Definition: scene.h:204
exotica::Scene::GetScene
std::string GetScene()
exotica::Scene::has_quaternion_floating_base_
bool has_quaternion_floating_base_
Whether the state includes a SE(3) floating base.
Definition: scene.h:185
exotica::Scene::UpdateTrajectoryGenerators
void UpdateTrajectoryGenerators(double t=0)
exotica::Scene::CleanScene
void CleanScene()
exotica::Scene::AddTrajectory
void AddTrajectory(const std::string &link, const std::string &traj)
exotica::Scene::LoadSceneFromStringStream
void LoadSceneFromStringStream(std::istream &in, const Eigen::Isometry3d &offset, bool update_collision_scene)
exotica::Scene::UpdateCollisionObjects
void UpdateCollisionObjects()
exotica::Scene::GetModelLinkNames
std::vector< std::string > GetModelLinkNames()
exotica::Scene::ps_
planning_scene::PlanningScenePtr ps_
Internal MoveIt planning scene.
Definition: scene.h:210
exotica::Scene::PublishScene
void PublishScene()
exotica::CollisionScenePtr
std::shared_ptr< CollisionScene > CollisionScenePtr
Definition: collision_scene.h:341
exotica::Scene::GetRootFrameName
std::string GetRootFrameName()
exotica::Scene::GetDynamicsSolver
std::shared_ptr< DynamicsSolver > GetDynamicsSolver() const
Returns a pointer to the CollisionScene.
exotica::Scene::get_num_velocities
int get_num_velocities() const
exotica::Scene::SetModelState
void SetModelState(Eigen::VectorXdRefConst x, double t=0, bool update_traj=true)
exotica::KinematicTree
Definition: kinematic_tree.h:142
exotica::Scene::get_num_controls
int get_num_controls() const
exotica::Scene::LoadSceneFile
void LoadSceneFile(const std::string &file_name, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
exotica::Scene::UpdateMoveItPlanningScene
void UpdateMoveItPlanningScene()
Updates the internal state of the MoveIt PlanningScene from Kinematica.
exotica::Scene::GetTreeMap
std::map< std::string, std::weak_ptr< KinematicElement > > GetTreeMap()
exotica::Scene::PublishProxies
void PublishProxies(const std::vector< CollisionProxy > &proxies)
exotica::Scene::LoadScene
void LoadScene(const std::string &scene, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
exotica::Scene::AddTrajectoryFromFile
void AddTrajectoryFromFile(const std::string &link, const std::string &traj)
exotica::Scene::AddObject
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)
exotica::Scene::Instantiate
virtual void Instantiate(const SceneInitializer &init)
exotica::Scene::GetControlledLinkNames
std::vector< std::string > GetControlledLinkNames()
exotica::Scene::get_world_links_to_exclude_from_collision_scene
const std::set< std::string > & get_world_links_to_exclude_from_collision_scene() const
Returns world links that are to be excluded from collision checking.
Definition: scene.h:176
exotica::Scene::RemoveObject
void RemoveObject(const std::string &name)
exotica::Scene::GetControlledJointToCollisionLinkMap
const std::map< std::string, std::vector< std::string > > & GetControlledJointToCollisionLinkMap() const
Returns a map between controlled robot joint names and associated collision link names....
Definition: scene.h:174
exotica::Scene::ProxyToMarker
visualization_msgs::Marker ProxyToMarker(const std::vector< CollisionProxy > &proxies, const std::string &frame)
exotica::KinematicsRequest
Definition: kinematic_tree.h:93
exotica::Scene::GetModelLinkToCollisionLinkMap
const std::map< std::string, std::vector< std::string > > & GetModelLinkToCollisionLinkMap() const
Returns a map between a model link name and the names of associated collision links.
Definition: scene.h:168
exotica::Scene::GetModelStateMap
std::map< std::string, double > GetModelStateMap()
exotica::Scene::custom_links_
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.
Definition: scene.h:221
exotica::Scene::num_state_derivative_
int num_state_derivative_
"ndx"
Definition: scene.h:207
exotica::Scene::GetModelLinkToCollisionElementMap
const std::map< std::string, std::vector< std::shared_ptr< KinematicElement > > > & GetModelLinkToCollisionElementMap() const
Returns a map between a model link name and the KinematicElement of associated collision links.
Definition: scene.h:171
exotica::Scene::UpdatePlanningSceneWorld
void UpdatePlanningSceneWorld(const moveit_msgs::PlanningSceneWorldConstPtr &world)
Update the collision scene from a moveit_msgs::PlanningSceneWorld.
exotica::Scene::Scene
Scene()
exotica::Scene::kinematic_solution_
std::shared_ptr< KinematicResponse > kinematic_solution_
Definition: scene.h:241
exotica::AttachedObject::pose
KDL::Frame pose
Definition: scene.h:59
exotica::DynamicsSolver
AbstractDynamicsSolver< double, Eigen::Dynamic, Eigen::Dynamic > DynamicsSolver
Definition: dynamics_solver.h:267
exotica::AttachedObject::AttachedObject
AttachedObject(std::string _parent)
Definition: scene.h:56
exotica::Scene::kinematica_
exotica::KinematicTree kinematica_
The kinematica tree.
Definition: scene.h:195
exotica::Scene::GetCollisionScene
const CollisionScenePtr & GetCollisionScene() const
Returns a pointer to the CollisionScene.
exotica::Scene::force_collision_
bool force_collision_
Definition: scene.h:225
kinematic_tree.h
object.h
exotica::Scene::dynamics_solver_
std::shared_ptr< DynamicsSolver > dynamics_solver_
The dynamics solver.
Definition: scene.h:201
exotica::Scene::GetControlledJointNames
std::vector< std::string > GetControlledJointNames()