Public Member Functions | Private Member Functions | Private Attributes | List of all members
exotica::Scene Class Reference

The class of EXOTica Scene. More...

#include <scene.h>

Inheritance diagram for exotica::Scene:
Inheritance graph
[legend]

Public Member Functions

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)
 
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 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 AddTrajectory (const std::string &link, const std::string &traj)
 
void AddTrajectory (const std::string &link, std::shared_ptr< Trajectory > traj)
 
void AddTrajectoryFromFile (const std::string &link, const std::string &traj)
 
bool AlwaysUpdatesCollisionScene () const
 Whether the collision scene transforms get updated on every scene update. More...
 
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. The relative transformation will be computed from current object and new parent transformations in the world frame. More...
 
void AttachObjectLocal (const std::string &name, const std::string &parent, const Eigen::VectorXd &pose)
 
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. More...
 
void CleanScene ()
 
void DetachObject (const std::string &name)
 Detaches an object and leaves it a at its current world location. This effectively attaches the object to the world frame. More...
 
bool get_has_quaternion_floating_base () const
 
int get_num_controls () const
 
int get_num_positions () const
 
int get_num_state () const
 
int get_num_state_derivative () const
 
int get_num_velocities () const
 
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. More...
 
const CollisionScenePtrGetCollisionScene () const
 Returns a pointer to the CollisionScene. More...
 
std::vector< std::string > GetControlledJointNames ()
 
const std::map< std::string, std::vector< std::string > > & GetControlledJointToCollisionLinkMap () const
 Returns a map between controlled robot joint names and associated collision link names. Here we consider all fixed links between controlled links as belonging to the previous controlled joint (as if the collision links had been fused). More...
 
std::vector< std::string > GetControlledLinkNames ()
 
Eigen::VectorXd GetControlledState ()
 
std::shared_ptr< DynamicsSolverGetDynamicsSolver () const
 Returns a pointer to the CollisionScene. More...
 
exotica::KinematicTreeGetKinematicTree ()
 
std::vector< std::string > GetModelJointNames ()
 
std::vector< std::string > GetModelLinkNames ()
 
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. More...
 
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. More...
 
Eigen::VectorXd GetModelState ()
 
std::map< std::string, double > GetModelStateMap ()
 
const std::string & GetName () const
 
moveit_msgs::PlanningScene GetPlanningSceneMsg ()
 Returns the current robot configuration and collision environment as a moveit_msgs::PlanningScene. More...
 
std::string GetRootFrameName ()
 
std::string GetRootJointName ()
 
std::string GetScene ()
 
std::shared_ptr< TrajectoryGetTrajectory (const std::string &link)
 
std::map< std::string, std::weak_ptr< KinematicElement > > GetTreeMap ()
 
bool HasAttachedObject (const std::string &name)
 
virtual void Instantiate (const SceneInitializer &init)
 
void LoadScene (const std::string &scene, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
 
void LoadScene (const std::string &scene, const KDL::Frame &offset=KDL::Frame(), bool update_collision_scene=true)
 
void LoadSceneFile (const std::string &file_name, const Eigen::Isometry3d &offset=Eigen::Isometry3d::Identity(), bool update_collision_scene=true)
 
void LoadSceneFile (const std::string &file_name, const KDL::Frame &offset=KDL::Frame(), bool update_collision_scene=true)
 
visualization_msgs::Marker ProxyToMarker (const std::vector< CollisionProxy > &proxies, const std::string &frame)
 
void PublishProxies (const std::vector< CollisionProxy > &proxies)
 
void PublishScene ()
 
void RemoveObject (const std::string &name)
 
void RemoveTrajectory (const std::string &link)
 
void RequestKinematics (KinematicsRequest &request, std::function< void(std::shared_ptr< KinematicResponse >)> callback)
 
 Scene ()
 
 Scene (const std::string &name)
 
void SetModelState (const std::map< std::string, double > &x, double t=0, bool update_traj=true)
 
void SetModelState (Eigen::VectorXdRefConst x, double t=0, bool update_traj=true)
 
void Update (Eigen::VectorXdRefConst x, double t=0)
 
void UpdateCollisionObjects ()
 
void UpdatePlanningScene (const moveit_msgs::PlanningScene &scene)
 Update the collision scene from a moveit_msgs::PlanningScene. More...
 
void UpdatePlanningSceneWorld (const moveit_msgs::PlanningSceneWorldConstPtr &world)
 Update the collision scene from a moveit_msgs::PlanningSceneWorld. More...
 
void UpdateSceneFrames ()
 Updates exotica scene object frames from the MoveIt scene. More...
 
void UpdateTrajectoryGenerators (double t=0)
 
virtual ~Scene ()
 
- Public Member Functions inherited from exotica::Object
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
 Object ()
 
virtual std::string Print (const std::string &prepend) const
 
virtual std::string type () const
 Type Information wrapper: must be virtual so that it is polymorphic... More...
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::Instantiable< SceneInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const SceneInitializer & GetParameters () const
 
void InstantiateInternal (const Initializer &init) override
 
- Public Member Functions inherited from exotica::InstantiableBase
virtual std::vector< InitializerGetAllTemplates () const =0
 
 InstantiableBase ()=default
 
virtual void InstantiateBase (const Initializer &)
 
virtual ~InstantiableBase ()=default
 

Private Member Functions

void LoadSceneFromStringStream (std::istream &in, const Eigen::Isometry3d &offset, bool update_collision_scene)
 
void UpdateInternalFrames (bool update_request=true)
 
void UpdateMoveItPlanningScene ()
 Updates the internal state of the MoveIt PlanningScene from Kinematica. More...
 
- Private Member Functions inherited from exotica::Uncopyable
 Uncopyable ()=default
 
 ~Uncopyable ()=default
 

Private Attributes

std::map< std::string, AttachedObjectattached_objects_
 List of attached objects These objects will be reattached if the scene gets reloaded. More...
 
CollisionScenePtr collision_scene_
 The collision scene. More...
 
std::map< std::string, std::vector< std::string > > controlled_joint_to_collision_link_map_
 Mapping between controlled joint name and collision links. More...
 
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. More...
 
std::shared_ptr< DynamicsSolverdynamics_solver_ = std::shared_ptr<DynamicsSolver>(nullptr)
 The dynamics solver. More...
 
bool force_collision_
 
bool has_quaternion_floating_base_ = false
 Whether the state includes a SE(3) floating base. More...
 
KinematicsRequest kinematic_request_
 
std::function< void(std::shared_ptr< KinematicResponse >)> kinematic_request_callback_
 
std::shared_ptr< KinematicResponsekinematic_solution_
 
exotica::KinematicTree kinematica_
 The kinematica tree. More...
 
std::map< std::string, std::vector< std::shared_ptr< KinematicElement > > > model_link_to_collision_element_map_
 
std::map< std::string, std::vector< std::string > > model_link_to_collision_link_map_
 Mapping between model link names and collision links. More...
 
int num_controls_ = 0
 "nu" More...
 
int num_positions_ = 0
 "nq" More...
 
int num_state_ = 0
 "nx" More...
 
int num_state_derivative_ = 0
 "ndx" More...
 
int num_velocities_ = 0
 "nv" More...
 
ros::Publisher proxy_pub_
 
planning_scene::PlanningScenePtr ps_
 Internal MoveIt planning scene. More...
 
ros::Publisher ps_pub_
 Visual debug. More...
 
bool request_needs_updating_
 
std::set< std::string > robot_links_to_exclude_from_collision_scene_
 List of robot links to be excluded from the collision scene. More...
 
std::map< std::string, std::pair< std::weak_ptr< KinematicElement >, std::shared_ptr< Trajectory > > > trajectory_generators_
 
std::set< std::string > world_links_to_exclude_from_collision_scene_
 List of world links to be excluded from the collision scene. More...
 

Additional Inherited Members

- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 
- Protected Attributes inherited from exotica::Instantiable< SceneInitializer >
SceneInitializer parameters_
 

Detailed Description

The class of EXOTica Scene.

Definition at line 69 of file scene.h.

Constructor & Destructor Documentation

◆ Scene() [1/2]

exotica::Scene::Scene ( const std::string &  name)

Definition at line 57 of file scene.cpp.

◆ Scene() [2/2]

exotica::Scene::Scene ( )
default

◆ ~Scene()

exotica::Scene::~Scene ( )
virtualdefault

Member Function Documentation

◆ AddObject() [1/2]

void exotica::Scene::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 
)

Definition at line 840 of file scene.cpp.

◆ AddObject() [2/2]

void exotica::Scene::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 
)

Definition at line 829 of file scene.cpp.

◆ AddObjectToEnvironment()

void exotica::Scene::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 
)

Definition at line 853 of file scene.cpp.

◆ AddTrajectory() [1/2]

void exotica::Scene::AddTrajectory ( const std::string &  link,
const std::string &  traj 
)

Definition at line 922 of file scene.cpp.

◆ AddTrajectory() [2/2]

void exotica::Scene::AddTrajectory ( const std::string &  link,
std::shared_ptr< Trajectory traj 
)

Definition at line 927 of file scene.cpp.

◆ AddTrajectoryFromFile()

void exotica::Scene::AddTrajectoryFromFile ( const std::string &  link,
const std::string &  traj 
)

Definition at line 917 of file scene.cpp.

◆ AlwaysUpdatesCollisionScene()

bool exotica::Scene::AlwaysUpdatesCollisionScene ( ) const
inline

Whether the collision scene transforms get updated on every scene update.

Returns
Whether collision scene transforms are force updated on every scene update.

Definition at line 165 of file scene.h.

◆ AttachObject()

void exotica::Scene::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. The relative transformation will be computed from current object and new parent transformations in the world frame.

Parameters
nameName of the object to attach.
parentName of the new parent frame.

Definition at line 887 of file scene.cpp.

◆ AttachObjectLocal() [1/2]

void exotica::Scene::AttachObjectLocal ( const std::string &  name,
const std::string &  parent,
const Eigen::VectorXd pose 
)

Definition at line 899 of file scene.cpp.

◆ AttachObjectLocal() [2/2]

void exotica::Scene::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.

Parameters
nameName of the object to attach.
parentName of the new parent frame.
poseRelative pose of the attached object in the new parent's local frame.

Definition at line 893 of file scene.cpp.

◆ CleanScene()

void exotica::Scene::CleanScene ( )

Definition at line 657 of file scene.cpp.

◆ DetachObject()

void exotica::Scene::DetachObject ( const std::string &  name)

Detaches an object and leaves it a at its current world location. This effectively attaches the object to the world frame.

Parameters
nameName of the object to detach.

Definition at line 904 of file scene.cpp.

◆ get_has_quaternion_floating_base()

bool exotica::Scene::get_has_quaternion_floating_base ( ) const

Definition at line 977 of file scene.cpp.

◆ get_num_controls()

int exotica::Scene::get_num_controls ( ) const

Definition at line 962 of file scene.cpp.

◆ get_num_positions()

int exotica::Scene::get_num_positions ( ) const

Definition at line 952 of file scene.cpp.

◆ get_num_state()

int exotica::Scene::get_num_state ( ) const

Definition at line 967 of file scene.cpp.

◆ get_num_state_derivative()

int exotica::Scene::get_num_state_derivative ( ) const

Definition at line 972 of file scene.cpp.

◆ get_num_velocities()

int exotica::Scene::get_num_velocities ( ) const

Definition at line 957 of file scene.cpp.

◆ get_world_links_to_exclude_from_collision_scene()

const std::set<std::string>& exotica::Scene::get_world_links_to_exclude_from_collision_scene ( ) const
inline

Returns world links that are to be excluded from collision checking.

Definition at line 176 of file scene.h.

◆ GetCollisionScene()

const CollisionScenePtr & exotica::Scene::GetCollisionScene ( ) const

Returns a pointer to the CollisionScene.

Definition at line 452 of file scene.cpp.

◆ GetControlledJointNames()

std::vector< std::string > exotica::Scene::GetControlledJointNames ( )

Definition at line 540 of file scene.cpp.

◆ GetControlledJointToCollisionLinkMap()

const std::map<std::string, std::vector<std::string> >& exotica::Scene::GetControlledJointToCollisionLinkMap ( ) const
inline

Returns a map between controlled robot joint names and associated collision link names. Here we consider all fixed links between controlled links as belonging to the previous controlled joint (as if the collision links had been fused).

Returns
Map between controlled joints and associated collision links.

Definition at line 174 of file scene.h.

◆ GetControlledLinkNames()

std::vector< std::string > exotica::Scene::GetControlledLinkNames ( )

Definition at line 545 of file scene.cpp.

◆ GetControlledState()

Eigen::VectorXd exotica::Scene::GetControlledState ( )

Definition at line 605 of file scene.cpp.

◆ GetDynamicsSolver()

std::shared_ptr< DynamicsSolver > exotica::Scene::GetDynamicsSolver ( ) const

Returns a pointer to the CollisionScene.

Definition at line 458 of file scene.cpp.

◆ GetKinematicTree()

exotica::KinematicTree & exotica::Scene::GetKinematicTree ( )

Definition at line 535 of file scene.cpp.

◆ GetModelJointNames()

std::vector< std::string > exotica::Scene::GetModelJointNames ( )

Definition at line 555 of file scene.cpp.

◆ GetModelLinkNames()

std::vector< std::string > exotica::Scene::GetModelLinkNames ( )

Definition at line 550 of file scene.cpp.

◆ GetModelLinkToCollisionElementMap()

const std::map<std::string, std::vector<std::shared_ptr<KinematicElement> > >& exotica::Scene::GetModelLinkToCollisionElementMap ( ) const
inline

Returns a map between a model link name and the KinematicElement of associated collision links.

Returns
Map between model links and all the KinematicElements of the associated collision links.

Definition at line 171 of file scene.h.

◆ GetModelLinkToCollisionLinkMap()

const std::map<std::string, std::vector<std::string> >& exotica::Scene::GetModelLinkToCollisionLinkMap ( ) const
inline

Returns a map between a model link name and the names of associated collision links.

Returns
Map between model links and all associated collision links.

Definition at line 168 of file scene.h.

◆ GetModelState()

Eigen::VectorXd exotica::Scene::GetModelState ( )

Definition at line 560 of file scene.cpp.

◆ GetModelStateMap()

std::map< std::string, double > exotica::Scene::GetModelStateMap ( )

Definition at line 565 of file scene.cpp.

◆ GetName()

const std::string & exotica::Scene::GetName ( ) const

Definition at line 64 of file scene.cpp.

◆ GetPlanningSceneMsg()

moveit_msgs::PlanningScene exotica::Scene::GetPlanningSceneMsg ( )

Returns the current robot configuration and collision environment as a moveit_msgs::PlanningScene.

Definition at line 473 of file scene.cpp.

◆ GetRootFrameName()

std::string exotica::Scene::GetRootFrameName ( )

Definition at line 463 of file scene.cpp.

◆ GetRootJointName()

std::string exotica::Scene::GetRootJointName ( )

Definition at line 468 of file scene.cpp.

◆ GetScene()

std::string exotica::Scene::GetScene ( )

Definition at line 649 of file scene.cpp.

◆ GetTrajectory()

std::shared_ptr< Trajectory > exotica::Scene::GetTrajectory ( const std::string &  link)

Definition at line 937 of file scene.cpp.

◆ GetTreeMap()

std::map< std::string, std::weak_ptr< KinematicElement > > exotica::Scene::GetTreeMap ( )

Definition at line 570 of file scene.cpp.

◆ HasAttachedObject()

bool exotica::Scene::HasAttachedObject ( const std::string &  name)

Definition at line 912 of file scene.cpp.

◆ Instantiate()

void exotica::Scene::Instantiate ( const SceneInitializer &  init)
virtual

Reimplemented from exotica::Instantiable< SceneInitializer >.

Definition at line 69 of file scene.cpp.

◆ LoadScene() [1/2]

void exotica::Scene::LoadScene ( const std::string &  scene,
const Eigen::Isometry3d &  offset = Eigen::Isometry3d::Identity(),
bool  update_collision_scene = true 
)

Definition at line 617 of file scene.cpp.

◆ LoadScene() [2/2]

void exotica::Scene::LoadScene ( const std::string &  scene,
const KDL::Frame &  offset = KDL::Frame(),
bool  update_collision_scene = true 
)

Definition at line 610 of file scene.cpp.

◆ LoadSceneFile() [1/2]

void exotica::Scene::LoadSceneFile ( const std::string &  file_name,
const Eigen::Isometry3d &  offset = Eigen::Isometry3d::Identity(),
bool  update_collision_scene = true 
)

Definition at line 630 of file scene.cpp.

◆ LoadSceneFile() [2/2]

void exotica::Scene::LoadSceneFile ( const std::string &  file_name,
const KDL::Frame &  offset = KDL::Frame(),
bool  update_collision_scene = true 
)

Definition at line 623 of file scene.cpp.

◆ LoadSceneFromStringStream()

void exotica::Scene::LoadSceneFromStringStream ( std::istream &  in,
const Eigen::Isometry3d &  offset,
bool  update_collision_scene 
)
private

Definition at line 637 of file scene.cpp.

◆ ProxyToMarker()

visualization_msgs::Marker exotica::Scene::ProxyToMarker ( const std::vector< CollisionProxy > &  proxies,
const std::string &  frame 
)

Definition at line 397 of file scene.cpp.

◆ PublishProxies()

void exotica::Scene::PublishProxies ( const std::vector< CollisionProxy > &  proxies)

Definition at line 389 of file scene.cpp.

◆ PublishScene()

void exotica::Scene::PublishScene ( )

Definition at line 381 of file scene.cpp.

◆ RemoveObject()

void exotica::Scene::RemoveObject ( const std::string &  name)

Definition at line 867 of file scene.cpp.

◆ RemoveTrajectory()

void exotica::Scene::RemoveTrajectory ( const std::string &  link)

Definition at line 944 of file scene.cpp.

◆ RequestKinematics()

void exotica::Scene::RequestKinematics ( KinematicsRequest request,
std::function< void(std::shared_ptr< KinematicResponse >)>  callback 
)

Definition at line 320 of file scene.cpp.

◆ SetModelState() [1/2]

void exotica::Scene::SetModelState ( const std::map< std::string, double > &  x,
double  t = 0,
bool  update_traj = true 
)

Definition at line 590 of file scene.cpp.

◆ SetModelState() [2/2]

void exotica::Scene::SetModelState ( Eigen::VectorXdRefConst  x,
double  t = 0,
bool  update_traj = true 
)

Definition at line 575 of file scene.cpp.

◆ Update()

void exotica::Scene::Update ( Eigen::VectorXdRefConst  x,
double  t = 0 
)

Definition at line 337 of file scene.cpp.

◆ UpdateCollisionObjects()

void exotica::Scene::UpdateCollisionObjects ( )

Definition at line 447 of file scene.cpp.

◆ UpdateInternalFrames()

void exotica::Scene::UpdateInternalFrames ( bool  update_request = true)
private

Definition at line 664 of file scene.cpp.

◆ UpdateMoveItPlanningScene()

void exotica::Scene::UpdateMoveItPlanningScene ( )
private

Updates the internal state of the MoveIt PlanningScene from Kinematica.

Definition at line 350 of file scene.cpp.

◆ UpdatePlanningScene()

void exotica::Scene::UpdatePlanningScene ( const moveit_msgs::PlanningScene &  scene)

Update the collision scene from a moveit_msgs::PlanningScene.

Parameters
[in]scenemoveit_msgs::PlanningScene

Definition at line 433 of file scene.cpp.

◆ UpdatePlanningSceneWorld()

void exotica::Scene::UpdatePlanningSceneWorld ( const moveit_msgs::PlanningSceneWorldConstPtr &  world)

Update the collision scene from a moveit_msgs::PlanningSceneWorld.

Parameters
[in]worldmoveit_msgs::PlanningSceneWorld

Definition at line 440 of file scene.cpp.

◆ UpdateSceneFrames()

void exotica::Scene::UpdateSceneFrames ( )

Updates exotica scene object frames from the MoveIt scene.

Definition at line 702 of file scene.cpp.

◆ UpdateTrajectoryGenerators()

void exotica::Scene::UpdateTrajectoryGenerators ( double  t = 0)

Definition at line 329 of file scene.cpp.

Member Data Documentation

◆ attached_objects_

std::map<std::string, AttachedObject> exotica::Scene::attached_objects_
private

List of attached objects These objects will be reattached if the scene gets reloaded.

Definition at line 218 of file scene.h.

◆ collision_scene_

CollisionScenePtr exotica::Scene::collision_scene_
private

The collision scene.

Definition at line 198 of file scene.h.

◆ controlled_joint_to_collision_link_map_

std::map<std::string, std::vector<std::string> > exotica::Scene::controlled_joint_to_collision_link_map_
private

Mapping between controlled joint name and collision links.

Definition at line 232 of file scene.h.

◆ custom_links_

std::vector<std::shared_ptr<KinematicElement> > exotica::Scene::custom_links_
private

List of frames/links added on top of robot links and scene objects defined in the MoveIt scene.

Definition at line 221 of file scene.h.

◆ dynamics_solver_

std::shared_ptr<DynamicsSolver> exotica::Scene::dynamics_solver_ = std::shared_ptr<DynamicsSolver>(nullptr)
private

The dynamics solver.

Definition at line 201 of file scene.h.

◆ force_collision_

bool exotica::Scene::force_collision_
private

Definition at line 225 of file scene.h.

◆ has_quaternion_floating_base_

bool exotica::Scene::has_quaternion_floating_base_ = false
private

Whether the state includes a SE(3) floating base.

Definition at line 185 of file scene.h.

◆ kinematic_request_

KinematicsRequest exotica::Scene::kinematic_request_
private

Definition at line 240 of file scene.h.

◆ kinematic_request_callback_

std::function<void(std::shared_ptr<KinematicResponse>)> exotica::Scene::kinematic_request_callback_
private

Definition at line 242 of file scene.h.

◆ kinematic_solution_

std::shared_ptr<KinematicResponse> exotica::Scene::kinematic_solution_
private

Definition at line 241 of file scene.h.

◆ kinematica_

exotica::KinematicTree exotica::Scene::kinematica_
private

The kinematica tree.

Definition at line 195 of file scene.h.

◆ model_link_to_collision_element_map_

std::map<std::string, std::vector<std::shared_ptr<KinematicElement> > > exotica::Scene::model_link_to_collision_element_map_
private

Definition at line 229 of file scene.h.

◆ model_link_to_collision_link_map_

std::map<std::string, std::vector<std::string> > exotica::Scene::model_link_to_collision_link_map_
private

Mapping between model link names and collision links.

Definition at line 228 of file scene.h.

◆ num_controls_

int exotica::Scene::num_controls_ = 0
private

"nu"

Definition at line 205 of file scene.h.

◆ num_positions_

int exotica::Scene::num_positions_ = 0
private

"nq"

Definition at line 203 of file scene.h.

◆ num_state_

int exotica::Scene::num_state_ = 0
private

"nx"

Definition at line 206 of file scene.h.

◆ num_state_derivative_

int exotica::Scene::num_state_derivative_ = 0
private

"ndx"

Definition at line 207 of file scene.h.

◆ num_velocities_

int exotica::Scene::num_velocities_ = 0
private

"nv"

Definition at line 204 of file scene.h.

◆ proxy_pub_

ros::Publisher exotica::Scene::proxy_pub_
private

Definition at line 214 of file scene.h.

◆ ps_

planning_scene::PlanningScenePtr exotica::Scene::ps_
private

Internal MoveIt planning scene.

Definition at line 210 of file scene.h.

◆ ps_pub_

ros::Publisher exotica::Scene::ps_pub_
private

Visual debug.

Definition at line 213 of file scene.h.

◆ request_needs_updating_

bool exotica::Scene::request_needs_updating_
private

Definition at line 243 of file scene.h.

◆ robot_links_to_exclude_from_collision_scene_

std::set<std::string> exotica::Scene::robot_links_to_exclude_from_collision_scene_
private

List of robot links to be excluded from the collision scene.

Definition at line 235 of file scene.h.

◆ trajectory_generators_

std::map<std::string, std::pair<std::weak_ptr<KinematicElement>, std::shared_ptr<Trajectory> > > exotica::Scene::trajectory_generators_
private

Definition at line 223 of file scene.h.

◆ world_links_to_exclude_from_collision_scene_

std::set<std::string> exotica::Scene::world_links_to_exclude_from_collision_scene_
private

List of world links to be excluded from the collision scene.

Definition at line 238 of file scene.h.


The documentation for this class was generated from the following files:


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sun Jun 2 2024 02:58:18