|
SMORES Robot Platform Simulation
Modlab at Penn, ASL at Cornell
|
The class that will be used to record the position information of a module. More...
#include <GaitRecorder.hh>
Public Member Functions | |
| PoseRecord () | |
| Constructor. | |
| PoseRecord (double joint0, double joint1, double joint2, double joint3, math::Pose pos) | |
| Constructor. More... | |
| void | UpdateJoints (double joint0, double joint1, double joint2, double joint3, math::Pose pos) |
| Update the current record. More... | |
Public Attributes | |
| double | JointAngles [4] |
| Joint angles of the module. | |
| math::Pose | Position |
| Global position of the module. | |
The class that will be used to record the position information of a module.
Record of the position of a single module at a specific point of simulation, so later the module can be reset to this position
| gazebo::PoseRecord::PoseRecord | ( | double | joint0, |
| double | joint1, | ||
| double | joint2, | ||
| double | joint3, | ||
| math::Pose | pos | ||
| ) |
Constructor.
| joint0 | Joint angle of joint 0 |
| joint1 | Joint angle of joint 1 |
| joint2 | Joint angle of joint 2 |
| joint3 | Joint angle of joint 3 |
| pos | Global position of the current module |
| void gazebo::PoseRecord::UpdateJoints | ( | double | joint0, |
| double | joint1, | ||
| double | joint2, | ||
| double | joint3, | ||
| math::Pose | pos | ||
| ) |
Update the current record.
| joint0 | Joint angle of joint 0 |
| joint1 | Joint angle of joint 1 |
| joint2 | Joint angle of joint 2 |
| joint3 | Joint angle of joint 3 |
| pos | Global position of the current module |