Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_SCENE_H_
31 #define EXOTICA_CORE_SCENE_H_
38 #include <geometric_shapes/shapes.h>
39 #include <moveit/planning_scene/planning_scene.h>
40 #include <moveit_msgs/PlanningScene.h>
49 #include <exotica_core/scene_initializer.h>
62 #ifndef EXOTICA_CORE_DYNAMICS_SOLVER_H_
63 template <
typename T,
int NX,
int NU>
72 Scene(
const std::string& name);
75 virtual void Instantiate(
const SceneInitializer& init);
77 const std::string&
GetName()
const;
97 std::map<std::string, std::weak_ptr<KinematicElement>>
GetTreeMap();
99 void SetModelState(
const std::map<std::string, double>& x,
double t = 0,
bool update_traj =
true);
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);
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);
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);
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);
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);
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);
201 std::shared_ptr<DynamicsSolver>
dynamics_solver_ = std::shared_ptr<DynamicsSolver>(
nullptr);
210 planning_scene::PlanningScenePtr
ps_;
249 #endif // EXOTICA_CORE_SCENE_H_
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
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
std::vector< std::string > GetModelJointNames()
AttachedObject(std::string _parent, KDL::Frame _pose)
Definition: scene.h:57
std::string GetRootJointName()
void Update(Eigen::VectorXdRefConst x, double t=0)
void DetachObject(const std::string &name)
Detaches an object and leaves it a at its current world location. This effectively attaches the objec...
int num_controls_
"nu"
Definition: scene.h:205
int get_num_positions() const
Definition: dynamics_solver.h:55
Eigen::VectorXd GetModelState()
Definition: uncopyable.h:35
int get_num_state_derivative() const
ros::Publisher proxy_pub_
Definition: scene.h:214
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....
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
std::string parent
Definition: scene.h:58
ros::Publisher ps_pub_
Visual debug.
Definition: scene.h:213
moveit_msgs::PlanningScene GetPlanningSceneMsg()
Returns the current robot configuration and collision environment as a moveit_msgs::PlanningScene.
The class of EXOTica Scene.
Definition: scene.h:69
void UpdatePlanningScene(const moveit_msgs::PlanningScene &scene)
Update the collision scene from a moveit_msgs::PlanningScene.
std::shared_ptr< Trajectory > GetTrajectory(const std::string &link)
bool get_has_quaternion_floating_base() const
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.
void UpdateSceneFrames()
Updates exotica scene object frames from the MoveIt scene.
KinematicsRequest kinematic_request_
Definition: scene.h:240
CollisionScenePtr collision_scene_
The collision scene.
Definition: scene.h:198
int num_positions_
"nq"
Definition: scene.h:203
std::map< std::string, std::pair< std::weak_ptr< KinematicElement >, std::shared_ptr< Trajectory > > > trajectory_generators_
Definition: scene.h:223
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
bool AlwaysUpdatesCollisionScene() const
Whether the collision scene transforms get updated on every scene update.
Definition: scene.h:165
Definition: property.h:110
int num_state_
"nx"
Definition: scene.h:206
const std::string & GetName() const
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
Definition: cartpole_dynamics_solver.h:38
exotica::KinematicTree & GetKinematicTree()
bool request_needs_updating_
Definition: scene.h:243
std::function< void(std::shared_ptr< KinematicResponse >)> kinematic_request_callback_
Definition: scene.h:242
void UpdateInternalFrames(bool update_request=true)
Eigen::VectorXd GetControlledState()
int get_num_state() const
std::map< std::string, std::vector< std::shared_ptr< KinematicElement > > > model_link_to_collision_element_map_
Definition: scene.h:229
bool HasAttachedObject(const std::string &name)
void RemoveTrajectory(const std::string &link)
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 RequestKinematics(KinematicsRequest &request, std::function< void(std::shared_ptr< KinematicResponse >)> callback)
std::shared_ptr< Scene > ScenePtr
Definition: scene.h:246
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
int num_velocities_
"nv"
Definition: scene.h:204
bool has_quaternion_floating_base_
Whether the state includes a SE(3) floating base.
Definition: scene.h:185
void UpdateTrajectoryGenerators(double t=0)
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()
std::vector< std::string > GetModelLinkNames()
planning_scene::PlanningScenePtr ps_
Internal MoveIt planning scene.
Definition: scene.h:210
std::shared_ptr< CollisionScene > CollisionScenePtr
Definition: collision_scene.h:341
std::string GetRootFrameName()
std::shared_ptr< DynamicsSolver > GetDynamicsSolver() const
Returns a pointer to the CollisionScene.
int get_num_velocities() const
void SetModelState(Eigen::VectorXdRefConst x, double t=0, bool update_traj=true)
Definition: kinematic_tree.h:142
int get_num_controls() const
void LoadSceneFile(const std::string &file_name, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
void UpdateMoveItPlanningScene()
Updates the internal state of the MoveIt PlanningScene from Kinematica.
std::map< std::string, std::weak_ptr< KinematicElement > > GetTreeMap()
void PublishProxies(const std::vector< CollisionProxy > &proxies)
void LoadScene(const std::string &scene, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
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)
virtual void Instantiate(const SceneInitializer &init)
std::vector< std::string > GetControlledLinkNames()
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
void RemoveObject(const std::string &name)
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
visualization_msgs::Marker ProxyToMarker(const std::vector< CollisionProxy > &proxies, const std::string &frame)
Definition: kinematic_tree.h:93
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
std::map< std::string, double > GetModelStateMap()
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
int num_state_derivative_
"ndx"
Definition: scene.h:207
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
void UpdatePlanningSceneWorld(const moveit_msgs::PlanningSceneWorldConstPtr &world)
Update the collision scene from a moveit_msgs::PlanningSceneWorld.
std::shared_ptr< KinematicResponse > kinematic_solution_
Definition: scene.h:241
KDL::Frame pose
Definition: scene.h:59
AbstractDynamicsSolver< double, Eigen::Dynamic, Eigen::Dynamic > DynamicsSolver
Definition: dynamics_solver.h:267
AttachedObject(std::string _parent)
Definition: scene.h:56
exotica::KinematicTree kinematica_
The kinematica tree.
Definition: scene.h:195
const CollisionScenePtr & GetCollisionScene() const
Returns a pointer to the CollisionScene.
bool force_collision_
Definition: scene.h:225
std::shared_ptr< DynamicsSolver > dynamics_solver_
The dynamics solver.
Definition: scene.h:201
std::vector< std::string > GetControlledJointNames()