KinematicsWorld.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2013-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package ArmarXSimulation::Simulator
19  * @author Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu )
20  * @date 2017
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
25 #pragma once
26 
27 #include <Eigen/Core>
28 #include <Eigen/Geometry>
29 
30 // just needed for SceneData
31 #include <ArmarXSimulation/interface/simulator/SimulatorInterface.h>
32 // #include <ArmarXCore/core/system/Synchronization.h>
37 
38 #include "SimulatedWorld.h"
39 
40 #include <mutex>
41 
42 namespace armarx
43 {
44  /*!
45  * \brief The KinematicsWorld class encapsulates the kinemtics simulation and the corresponding data.
46  * All real physics simulation is either approximated through simple kinemtics or disabled.
47  *
48  */
50  {
51  public:
52 
54  ~KinematicsWorld() override;
55 
56  virtual void initialize(int stepSizeMS, float maxRealTimeSimSpeed = 1, bool floorPlane = false, std::string floorTexture = std::string());
57 
58  //! ignoring velocity target
59  void actuateRobotJoints(const std::string& robotName, const std::map< std::string, float>& angles, const std::map< std::string, float>& velocities) override;
60  void actuateRobotJointsPos(const std::string& robotName, const std::map< std::string, float>& angles) override;
61  void actuateRobotJointsVel(const std::string& robotName, const std::map< std::string, float>& velocities) override;
62  void actuateRobotJointsTorque(const std::string& robotName, const std::map< std::string, float>& torques) override;
63  void setRobotPose(const std::string& robotName, const Eigen::Matrix4f& globalPose) override;
64 
65  void applyForceRobotNode(const std::string& robotName, const std::string& robotNodeName, const Eigen::Vector3f& force) override;
66  void applyTorqueRobotNode(const std::string& robotName, const std::string& robotNodeName, const Eigen::Vector3f& torque) override;
67 
68  void applyForceObject(const std::string& objectName, const Eigen::Vector3f& force) override;
69  void applyTorqueObject(const std::string& objectName, const Eigen::Vector3f& torque) override;
70 
71  bool hasObject(const std::string& instanceName) override;
72  void setObjectPose(const std::string& objectName, const Eigen::Matrix4f& globalPose) override;
73 
74  bool hasRobot(const std::string& robotName) override;
75  bool hasRobotNode(const std::string& robotName, const std::string& robotNodeName) override;
76  float getRobotMass(const std::string& robotName) override;
77 
78  std::map< std::string, float> getRobotJointAngles(const std::string& robotName) override;
79  float getRobotJointAngle(const std::string& robotName, const std::string& nodeName) override;
80  std::map< std::string, float> getRobotJointVelocities(const std::string& robotName) override;
81  float getRobotJointVelocity(const std::string& robotName, const std::string& nodeName) override;
82  std::map< std::string, float> getRobotJointTorques(const std::string&) override;
83  ForceTorqueDataSeq getRobotForceTorqueSensors(const std::string&) override;
84 
85  float getRobotJointLimitLo(const std::string& robotName, const std::string& nodeName) override;
86  float getRobotJointLimitHi(const std::string& robotName, const std::string& nodeName) override;
87  Eigen::Matrix4f getRobotPose(const std::string& robotName) override;
88 
89  float getRobotMaxTorque(const std::string& robotName, const std::string& nodeName) override;
90  void setRobotMaxTorque(const std::string& robotName, const std::string& nodeName, float maxTorque) override;
91 
92  Eigen::Matrix4f getRobotNodePose(const std::string& robotName, const std::string& robotNodeName) override;
93 
94  Eigen::Vector3f getRobotLinearVelocity(const std::string& robotName, const std::string& nodeName) override;
95  Eigen::Vector3f getRobotAngularVelocity(const std::string& robotName, const std::string& nodeName) override;
96 
97  // the robotNodeName is ignored, the whole robot is moved...
98  void setRobotLinearVelocity(const std::string& robotName, const std::string& robotNodeName, const Eigen::Vector3f& vel) override;
99  void setRobotAngularVelocity(const std::string& robotName, const std::string& robotNodeName, const Eigen::Vector3f& vel) override;
100  void setRobotLinearVelocityRobotRootFrame(const std::string& robotName, const std::string& robotNodeName, const Eigen::Vector3f& vel) override;
101  void setRobotAngularVelocityRobotRootFrame(const std::string& robotName, const std::string& robotNodeName, const Eigen::Vector3f& vel) override;
102 
103  Eigen::Matrix4f getObjectPose(const std::string& objectName) override;
104 
105  VirtualRobot::RobotPtr getRobot(const std::string& robotName) override;
106  std::map<std::string, VirtualRobot::RobotPtr> getRobots() override;
107  virtual VirtualRobot::SceneObjectPtr getObject(const std::string& objectName);
108  std::vector<VirtualRobot::SceneObjectPtr> getObjects() override;
109 
110  std::vector<SimDynamics::DynamicsEngine::DynamicsContactInfo> copyContacts() override;
111 
112 
113  FramedPosePtr toFramedPose(const Eigen::Matrix4f& globalPose, const std::string& robotName, const std::string& frameName) override;
114 
115  /**
116  * Perform one simulation step. Calculates the delta update time from the time that has passed since the last call.
117  * This updates all models.
118  */
119  void stepPhysicsRealTime() override;
120 
121  /**
122  * Perform one simulation step.
123  * This updates all models.
124  */
125  void stepPhysicsFixedTimeStep() override;
126 
127  /*!
128  * \brief
129  * \return The number of steps * the timestep in MS
130  */
131  int getFixedTimeStepMS() override;
132 
133 
134  void enableLogging(const std::string& robotName, const std::string& logFile) override;
135 
136  armarx::DistanceInfo getRobotNodeDistance(const std::string& robotName, const std::string& robotNodeName1, const std::string& robotNodeName2) override;
137  armarx::DistanceInfo getDistance(const std::string& robotName, const std::string& robotNodeName, const std::string& worldObjectName) override;
138 
139  std::vector<std::string> getRobotNames() override;
140  std::vector<std::string> getObstacleNames() override;
141 
142  void setRobotNodeSimType(const std::string& robotName, const std::string& robotNodeName, VirtualRobot::SceneObject::Physics::SimulationType simType) override;
143  void setObjectSimType(const std::string& objectName, VirtualRobot::SceneObject::Physics::SimulationType simType) override;
144 
145  protected:
146  bool addObstacleEngine(VirtualRobot::SceneObjectPtr o, VirtualRobot::SceneObject::Physics::SimulationType simType) override;
147  bool removeObstacleEngine(const std::string& name) override;
148  bool addRobotEngine(VirtualRobot::RobotPtr robot, double pid_p, double pid_i, double pid_d, const std::string& filename, bool staticRobot, bool selfCollisions) override;
149 
150  //! create a joint
151  bool objectGraspedEngine(const std::string& robotName, const std::string& robotNodeName, const std::string& objectName, Eigen::Matrix4f& storeLocalTransform) override;
152 
153  //! remove a joint
154  bool objectReleasedEngine(const std::string& robotName, const std::string& robotNodeName, const std::string& objectName) override;
155 
156  bool removeRobotEngine(const std::string& robotName) override;
157  bool synchronizeSimulationDataEngine() override;
158 
159  void setupFloorEngine(bool enable, const std::string& floorTexture) override;
160 
161  bool synchronizeObjects() override;
162 
163  bool getRobotStatus(const std::string& robotName,
167  Eigen::Vector3f& linearVelocity,
168  Eigen::Vector3f& angularVelocity) override;
169 
170  bool updateForceTorqueSensor(ForceTorqueInfo& ftInfo) override;
171 
172  bool synchronizeSceneObjectPoses(VirtualRobot::SceneObjectPtr currentObjEngine, std::map< std::string, armarx::PoseBasePtr >& objMap) override;
173 
175 
176  // manually apply velocities to static robots
177  void stepStaticRobots(double deltaInSeconds);
178  void stepStaticObjects(double deltaInSeconds);
179 
181 
183  {
185  {
186  velTransTarget.setZero();
187  velRotTarget.setZero();
188  velTransActual.setZero();
189  velRotActual.setZero();
190  }
191 
193  std::map< std::string, float> targetVelocities;
194  std::map< std::string, float> actualVelocities;
195  Eigen::Vector3f velTransTarget, velTransActual;
196  Eigen::Vector3f velRotTarget, velRotActual;
197  };
198 
199  std::map<std::string, KinematicRobotInfo> kinematicRobots;
200  std::vector<VirtualRobot::SceneObjectPtr> kinematicObjects;
201  std::map<VirtualRobot::RobotNodePtr, std::pair<IceUtil::Time, float> > jointAngleDerivationFilters;
202  std::map<VirtualRobot::RobotPtr, std::pair<IceUtil::Time, Eigen::Vector3f> > linearVelocityFilters;
203  std::map<VirtualRobot::RobotPtr, std::pair<IceUtil::Time, Eigen::Matrix4f>> angularVelocityFilters;
205  Eigen::Vector3f floorPos;
206  Eigen::Vector3f floorUp;
208  double floorDepthMM;
209  VirtualRobot::ObstaclePtr groundObject;
210  virtual void createFloorPlane(const Eigen::Vector3f& pos, const Eigen::Vector3f& up);
211 
213 
214  float getDeltaTimeMilli();
215 
216  bool synchronizeRobotNodePoses(const std::string& robotName, std::map<std::string, armarx::PoseBasePtr>& objMap) override;
218  };
219 
220  using KinematicsWorldPtr = std::shared_ptr<KinematicsWorld>;
221 }
222 
223 
DerivationFilter.h
armarx::KinematicsWorld::getRobotJointTorques
std::map< std::string, float > getRobotJointTorques(const std::string &) override
Definition: KinematicsWorld.cpp:359
armarx::KinematicsWorld::~KinematicsWorld
~KinematicsWorld() override
armarx::KinematicsWorld::getRobotJointLimitLo
float getRobotJointLimitLo(const std::string &robotName, const std::string &nodeName) override
Definition: KinematicsWorld.cpp:369
armarx::KinematicsWorld::initialize
virtual void initialize(int stepSizeMS, float maxRealTimeSimSpeed=1, bool floorPlane=false, std::string floorTexture=std::string())
Definition: KinematicsWorld.cpp:59
armarx::KinematicsWorld::getRobots
std::map< std::string, VirtualRobot::RobotPtr > getRobots() override
Definition: KinematicsWorld.cpp:675
armarx::KinematicsWorld::createFloorPlane
virtual void createFloorPlane(const Eigen::Vector3f &pos, const Eigen::Vector3f &up)
Definition: KinematicsWorld.cpp:77
armarx::KinematicsWorld::setRobotAngularVelocity
void setRobotAngularVelocity(const std::string &robotName, const std::string &robotNodeName, const Eigen::Vector3f &vel) override
Definition: KinematicsWorld.cpp:562
armarx::KinematicsWorld::jointAngleDerivationFilters
std::map< VirtualRobot::RobotNodePtr, std::pair< IceUtil::Time, float > > jointAngleDerivationFilters
Definition: KinematicsWorld.h:201
armarx::KinematicsWorld::getObstacleNames
std::vector< std::string > getObstacleNames() override
Definition: KinematicsWorld.cpp:1195
armarx::KinematicsWorld::getDeltaTimeMilli
float getDeltaTimeMilli()
Definition: KinematicsWorld.cpp:1459
armarx::KinematicsWorld::getObject
virtual VirtualRobot::SceneObjectPtr getObject(const std::string &objectName)
Definition: KinematicsWorld.cpp:687
armarx::KinematicsWorld::hasRobot
bool hasRobot(const std::string &robotName) override
Definition: KinematicsWorld.cpp:630
armarx::KinematicsWorld::getFloor
VirtualRobot::SceneObjectPtr getFloor() override
Definition: KinematicsWorld.cpp:797
armarx::KinematicsWorld::applyForceObject
void applyForceObject(const std::string &objectName, const Eigen::Vector3f &force) override
Definition: KinematicsWorld.cpp:216
armarx::KinematicsWorld::setObjectPose
void setObjectPose(const std::string &objectName, const Eigen::Matrix4f &globalPose) override
Definition: KinematicsWorld.cpp:234
armarx::KinematicsWorldPtr
std::shared_ptr< KinematicsWorld > KinematicsWorldPtr
Definition: KinematicsWorld.h:220
armarx::KinematicsWorld::kinematicObjects
std::vector< VirtualRobot::SceneObjectPtr > kinematicObjects
Definition: KinematicsWorld.h:200
armarx::KinematicsWorld::toFramedPose
FramedPosePtr toFramedPose(const Eigen::Matrix4f &globalPose, const std::string &robotName, const std::string &frameName) override
toFramedPose Constructs a framed pose
Definition: KinematicsWorld.cpp:863
armarx::KinematicsWorld::floorPos
Eigen::Vector3f floorPos
Definition: KinematicsWorld.h:205
armarx::KinematicsWorld::setObjectSimType
void setObjectSimType(const std::string &objectName, VirtualRobot::SceneObject::Physics::SimulationType simType) override
Definition: KinematicsWorld.cpp:1165
armarx::KinematicsWorld::enableLogging
void enableLogging(const std::string &robotName, const std::string &logFile) override
Definition: KinematicsWorld.cpp:1409
armarx::KinematicsWorld::getRobotNames
std::vector< std::string > getRobotNames() override
Definition: KinematicsWorld.cpp:1150
armarx::KinematicsWorld::setRobotLinearVelocityRobotRootFrame
void setRobotLinearVelocityRobotRootFrame(const std::string &robotName, const std::string &robotNodeName, const Eigen::Vector3f &vel) override
Definition: KinematicsWorld.cpp:581
armarx::KinematicsWorld::getRobotJointVelocities
std::map< std::string, float > getRobotJointVelocities(const std::string &robotName) override
Definition: KinematicsWorld.cpp:312
Pose.h
armarx::KinematicsWorld::KinematicRobotInfo::KinematicRobotInfo
KinematicRobotInfo()
Definition: KinematicsWorld.h:184
armarx::KinematicsWorld::getRobotJointVelocity
float getRobotJointVelocity(const std::string &robotName, const std::string &nodeName) override
Definition: KinematicsWorld.cpp:331
armarx::SimulatedWorld::maxRealTimeSimSpeed
float maxRealTimeSimSpeed
Definition: SimulatedWorld.h:453
armarx::KinematicsWorld::stepStaticRobots
void stepStaticRobots(double deltaInSeconds)
Definition: KinematicsWorld.cpp:1301
armarx::ForceTorqueInfo
Definition: SimulatedWorld.h:48
armarx::KinematicsWorld::objectReleasedEngine
bool objectReleasedEngine(const std::string &robotName, const std::string &robotNodeName, const std::string &objectName) override
remove a joint
Definition: KinematicsWorld.cpp:719
armarx::KinematicsWorld::applyTorqueRobotNode
void applyTorqueRobotNode(const std::string &robotName, const std::string &robotNodeName, const Eigen::Vector3f &torque) override
Definition: KinematicsWorld.cpp:210
armarx::KinematicsWorld::hasObject
bool hasObject(const std::string &instanceName) override
Definition: KinematicsWorld.cpp:229
armarx::SimulatedWorld
The SimulatedWorld class encapsulates the whole physics simulation and the corresponding data.
Definition: SimulatedWorld.h:128
armarx::KinematicsWorld::lastTime
IceUtil::Time lastTime
Definition: KinematicsWorld.h:212
armarx::KinematicsWorld::stepPhysicsFixedTimeStep
void stepPhysicsFixedTimeStep() override
Perform one simulation step.
Definition: KinematicsWorld.cpp:1265
armarx::KinematicsWorld::KinematicRobotInfo::actualVelocities
std::map< std::string, float > actualVelocities
Definition: KinematicsWorld.h:194
armarx::navigation::platform_controller::platform_global_trajectory::NameValueMap
std::map< std::string, float > NameValueMap
Definition: PlatformGlobalTrajectoryController.h:93
armarx::KinematicsWorld::KinematicRobotInfo::velRotActual
Eigen::Vector3f velRotActual
Definition: KinematicsWorld.h:196
armarx::KinematicsWorld::floorExtendMM
double floorExtendMM
Definition: KinematicsWorld.h:207
armarx::KinematicsWorld::getRobotMaxTorque
float getRobotMaxTorque(const std::string &robotName, const std::string &nodeName) override
Definition: KinematicsWorld.cpp:424
armarx::KinematicsWorld::angularVelocityFilters
std::map< VirtualRobot::RobotPtr, std::pair< IceUtil::Time, Eigen::Matrix4f > > angularVelocityFilters
Definition: KinematicsWorld.h:203
armarx::KinematicsWorld::KinematicsWorld
KinematicsWorld()
Definition: KinematicsWorld.cpp:45
armarx::KinematicsWorld::actuateRobotJointsVel
void actuateRobotJointsVel(const std::string &robotName, const std::map< std::string, float > &velocities) override
Definition: KinematicsWorld.cpp:161
armarx::KinematicsWorld::applyForceRobotNode
void applyForceRobotNode(const std::string &robotName, const std::string &robotNodeName, const Eigen::Vector3f &force) override
Definition: KinematicsWorld.cpp:204
armarx::KinematicsWorld::actuateRobotJoints
void actuateRobotJoints(const std::string &robotName, const std::map< std::string, float > &angles, const std::map< std::string, float > &velocities) override
ignoring velocity target
Definition: KinematicsWorld.cpp:115
armarx::KinematicsWorld::copyContacts
std::vector< SimDynamics::DynamicsEngine::DynamicsContactInfo > copyContacts() override
Definition: KinematicsWorld.cpp:1381
armarx::KinematicsWorld::getDistance
armarx::DistanceInfo getDistance(const std::string &robotName, const std::string &robotNodeName, const std::string &worldObjectName) override
Definition: KinematicsWorld.cpp:1509
armarx::KinematicsWorld::floorDepthMM
double floorDepthMM
Definition: KinematicsWorld.h:208
armarx::KinematicsWorld::objectGraspedEngine
bool objectGraspedEngine(const std::string &robotName, const std::string &robotNodeName, const std::string &objectName, Eigen::Matrix4f &storeLocalTransform) override
create a joint
Definition: KinematicsWorld.cpp:754
armarx::KinematicsWorld::removeObstacleEngine
bool removeObstacleEngine(const std::string &name) override
Definition: KinematicsWorld.cpp:1210
IceInternal::Handle< FramedPose >
armarx::KinematicsWorld::stepSizeMs
int stepSizeMs
Definition: KinematicsWorld.h:180
armarx::KinematicsWorld::updateForceTorqueSensor
bool updateForceTorqueSensor(ForceTorqueInfo &ftInfo) override
Definition: KinematicsWorld.cpp:1095
armarx::KinematicsWorld::synchronizeSimulationDataEngine
bool synchronizeSimulationDataEngine() override
Definition: KinematicsWorld.cpp:1440
armarx::KinematicsWorld::KinematicRobotInfo::velTransActual
Eigen::Vector3f velTransActual
Definition: KinematicsWorld.h:195
armarx::KinematicsWorld::getRobotNodePose
Eigen::Matrix4f getRobotNodePose(const std::string &robotName, const std::string &robotNodeName) override
Definition: KinematicsWorld.cpp:466
FramedPose.h
armarx::KinematicsWorld::getObjectPose
Eigen::Matrix4f getObjectPose(const std::string &objectName) override
Definition: KinematicsWorld.cpp:704
armarx::KinematicsWorld::getRobotJointAngles
std::map< std::string, float > getRobotJointAngles(const std::string &robotName) override
Definition: KinematicsWorld.cpp:263
armarx::KinematicsWorld::getRobotNodeDistance
armarx::DistanceInfo getRobotNodeDistance(const std::string &robotName, const std::string &robotNodeName1, const std::string &robotNodeName2) override
Definition: KinematicsWorld.cpp:1477
armarx::KinematicsWorld::hasRobotNode
bool hasRobotNode(const std::string &robotName, const std::string &robotNodeName) override
Definition: KinematicsWorld.cpp:647
armarx::KinematicsWorld::addRobotEngine
bool addRobotEngine(VirtualRobot::RobotPtr robot, double pid_p, double pid_i, double pid_d, const std::string &filename, bool staticRobot, bool selfCollisions) override
Definition: KinematicsWorld.cpp:824
armarx::KinematicsWorld::KinematicRobotInfo::velTransTarget
Eigen::Vector3f velTransTarget
Definition: KinematicsWorld.h:195
armarx::KinematicsWorld::calculateActualVelocities
void calculateActualVelocities()
Definition: KinematicsWorld.cpp:911
armarx::KinematicsWorld::kinematicRobots
std::map< std::string, KinematicRobotInfo > kinematicRobots
Definition: KinematicsWorld.h:199
filename
std::string filename
Definition: VisualizationRobot.cpp:84
armarx::channels::KinematicUnitObserver::jointVelocities
const KinematicUnitDatafieldCreator jointVelocities("jointVelocities")
armarx::KinematicsWorld::getObjects
std::vector< VirtualRobot::SceneObjectPtr > getObjects() override
Definition: KinematicsWorld.cpp:1387
armarx::KinematicsWorld::floor
VirtualRobot::SceneObjectPtr floor
Definition: KinematicsWorld.h:204
armarx::KinematicsWorld::synchronizeRobotNodePoses
bool synchronizeRobotNodePoses(const std::string &robotName, std::map< std::string, armarx::PoseBasePtr > &objMap) override
Definition: KinematicsWorld.cpp:888
armarx::KinematicsWorld::getRobotForceTorqueSensors
ForceTorqueDataSeq getRobotForceTorqueSensors(const std::string &) override
Definition: KinematicsWorld.cpp:364
armarx::KinematicsWorld::KinematicRobotInfo
Definition: KinematicsWorld.h:182
armarx::KinematicsWorld::groundObject
VirtualRobot::ObstaclePtr groundObject
Definition: KinematicsWorld.h:209
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::KinematicsWorld::KinematicRobotInfo::velRotTarget
Eigen::Vector3f velRotTarget
Definition: KinematicsWorld.h:196
armarx::KinematicsWorld::stepStaticObjects
void stepStaticObjects(double deltaInSeconds)
Definition: KinematicsWorld.cpp:1344
armarx::channels::KinematicUnitObserver::jointAngles
const KinematicUnitDatafieldCreator jointAngles("jointAngles")
armarx::KinematicsWorld::getRobotAngularVelocity
Eigen::Vector3f getRobotAngularVelocity(const std::string &robotName, const std::string &nodeName) override
Definition: KinematicsWorld.cpp:505
armarx::KinematicsWorld::setupFloorEngine
void setupFloorEngine(bool enable, const std::string &floorTexture) override
Definition: KinematicsWorld.cpp:1392
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::KinematicsWorld::actuateRobotJointsTorque
void actuateRobotJointsTorque(const std::string &robotName, const std::map< std::string, float > &torques) override
Definition: KinematicsWorld.cpp:181
armarx::KinematicsWorld::getRobot
VirtualRobot::RobotPtr getRobot(const std::string &robotName) override
Definition: KinematicsWorld.cpp:662
armarx::KinematicsWorld
The KinematicsWorld class encapsulates the kinemtics simulation and the corresponding data....
Definition: KinematicsWorld.h:49
armarx::KinematicsWorld::getRobotPose
Eigen::Matrix4f getRobotPose(const std::string &robotName) override
Definition: KinematicsWorld.cpp:409
armarx::KinematicsWorld::getRobotJointAngle
float getRobotJointAngle(const std::string &robotName, const std::string &nodeName) override
Definition: KinematicsWorld.cpp:290
armarx::KinematicsWorld::setRobotMaxTorque
void setRobotMaxTorque(const std::string &robotName, const std::string &nodeName, float maxTorque) override
Definition: KinematicsWorld.cpp:445
armarx::KinematicsWorld::setRobotLinearVelocity
void setRobotLinearVelocity(const std::string &robotName, const std::string &robotNodeName, const Eigen::Vector3f &vel) override
Definition: KinematicsWorld.cpp:545
scene3D::SceneObjectPtr
boost::intrusive_ptr< SceneObject > SceneObjectPtr
Definition: PointerDefinitions.h:40
armarx::KinematicsWorld::getFixedTimeStepMS
int getFixedTimeStepMS() override
Definition: KinematicsWorld.cpp:1376
armarx::KinematicsWorld::setRobotAngularVelocityRobotRootFrame
void setRobotAngularVelocityRobotRootFrame(const std::string &robotName, const std::string &robotNodeName, const Eigen::Vector3f &vel) override
Definition: KinematicsWorld.cpp:606
SimulatedWorld.h
armarx::KinematicsWorld::stepPhysicsRealTime
void stepPhysicsRealTime() override
Perform one simulation step.
Definition: KinematicsWorld.cpp:1239
armarx::KinematicsWorld::setRobotNodeSimType
void setRobotNodeSimType(const std::string &robotName, const std::string &robotNodeName, VirtualRobot::SceneObject::Physics::SimulationType simType) override
Definition: KinematicsWorld.cpp:1177
armarx::KinematicsWorld::getRobotJointLimitHi
float getRobotJointLimitHi(const std::string &robotName, const std::string &nodeName) override
Definition: KinematicsWorld.cpp:389
armarx::KinematicsWorld::linearVelocityFilters
std::map< VirtualRobot::RobotPtr, std::pair< IceUtil::Time, Eigen::Vector3f > > linearVelocityFilters
Definition: KinematicsWorld.h:202
armarx::KinematicsWorld::applyTorqueObject
void applyTorqueObject(const std::string &objectName, const Eigen::Vector3f &torque) override
Definition: KinematicsWorld.cpp:222
armarx::KinematicsWorld::KinematicRobotInfo::robot
VirtualRobot::RobotPtr robot
Definition: KinematicsWorld.h:192
armarx::KinematicsWorld::floorUp
Eigen::Vector3f floorUp
Definition: KinematicsWorld.h:206
armarx::channels::KinematicUnitObserver::jointTorques
const KinematicUnitDatafieldCreator jointTorques("jointTorques")
armarx::KinematicsWorld::getRobotStatus
bool getRobotStatus(const std::string &robotName, NameValueMap &jointAngles, NameValueMap &jointVelocities, NameValueMap &jointTorques, Eigen::Vector3f &linearVelocity, Eigen::Vector3f &angularVelocity) override
Definition: KinematicsWorld.cpp:1032
armarx::KinematicsWorld::synchronizeSceneObjectPoses
bool synchronizeSceneObjectPoses(VirtualRobot::SceneObjectPtr currentObjEngine, std::map< std::string, armarx::PoseBasePtr > &objMap) override
Definition: KinematicsWorld.cpp:1417
armarx::KinematicsWorld::getRobotLinearVelocity
Eigen::Vector3f getRobotLinearVelocity(const std::string &robotName, const std::string &nodeName) override
Definition: KinematicsWorld.cpp:488
armarx::KinematicsWorld::getRobotMass
float getRobotMass(const std::string &robotName) override
Definition: KinematicsWorld.cpp:249
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::KinematicsWorld::setRobotPose
void setRobotPose(const std::string &robotName, const Eigen::Matrix4f &globalPose) override
Definition: KinematicsWorld.cpp:189
armarx::KinematicsWorld::synchronizeObjects
bool synchronizeObjects() override
Definition: KinematicsWorld.cpp:1105
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
armarx::KinematicsWorld::removeRobotEngine
bool removeRobotEngine(const std::string &robotName) override
Definition: KinematicsWorld.cpp:804
armarx::KinematicsWorld::actuateRobotJointsPos
void actuateRobotJointsPos(const std::string &robotName, const std::map< std::string, float > &angles) override
Definition: KinematicsWorld.cpp:136
armarx::KinematicsWorld::KinematicRobotInfo::targetVelocities
std::map< std::string, float > targetVelocities
Definition: KinematicsWorld.h:193
armarx::KinematicsWorld::addObstacleEngine
bool addObstacleEngine(VirtualRobot::SceneObjectPtr o, VirtualRobot::SceneObject::Physics::SimulationType simType) override
Definition: KinematicsWorld.cpp:1135