Classes | |
| struct | ForceLimits |
| struct | ForceUtil |
| Map from force names to force ids. More... | |
| struct | JointLimits |
| struct | JointUtil |
| Map from joint names to joint ids. More... | |
Enumerations | |
| enum | ForceID { FORCE_ID_RIGHT_FOOT = 0, FORCE_ID_LEFT_FOOT = 1, FORCE_ID_RIGHT_HAND = 2, FORCE_ID_LEFT_HAND = 3 } |
Functions | |
| bool | base_se3_to_sot (dg::sot::ConstRefVector pos, dg::sot::ConstRefMatrix R, dg::sot::RefVector q_sot) |
| bool | base_se3_to_sot (dynamicgraph::sot::ConstRefVector pos, dynamicgraph::sot::ConstRefMatrix R, dynamicgraph::sot::RefVector q_sot) |
| bool | base_sot_to_urdf (dg::sot::ConstRefVector q_sot, dg::sot::RefVector q_urdf) |
| bool | base_sot_to_urdf (dynamicgraph::sot::ConstRefVector q_sot, dynamicgraph::sot::RefVector q_urdf) |
| bool | base_urdf_to_sot (dg::sot::ConstRefVector q_urdf, dg::sot::RefVector q_sot) |
| bool | base_urdf_to_sot (dynamicgraph::sot::ConstRefVector q_urdf, dynamicgraph::sot::RefVector q_sot) |
| bool | config_sot_to_urdf (dg::sot::ConstRefVector q_sot, dg::sot::RefVector q_urdf) |
| bool | config_sot_to_urdf (dynamicgraph::sot::ConstRefVector q_sot, dynamicgraph::sot::RefVector q_urdf) |
| bool | config_urdf_to_sot (dg::sot::ConstRefVector q_urdf, dg::sot::RefVector q_sot) |
| bool | config_urdf_to_sot (dynamicgraph::sot::ConstRefVector q_urdf, dynamicgraph::sot::RefVector q_sot) |
| bool | joints_sot_to_urdf (dynamicgraph::sot::ConstRefVector q_sot, dynamicgraph::sot::RefVector q_urdf) |
| bool | joints_sot_to_urdf (dg::sot::ConstRefVector q_sot, dg::sot::RefVector q_urdf) |
| bool | joints_urdf_to_sot (dg::sot::ConstRefVector q_urdf, dg::sot::RefVector q_sot) |
| bool | joints_urdf_to_sot (dynamicgraph::sot::ConstRefVector q_urdf, dynamicgraph::sot::RefVector q_sot) |
| bool | velocity_sot_to_urdf (dg::sot::ConstRefVector v_sot, dg::sot::RefVector v_urdf) |
| bool | velocity_sot_to_urdf (dynamicgraph::sot::ConstRefVector v_sot, dynamicgraph::sot::RefVector v_urdf) |
| bool | velocity_urdf_to_sot (dg::sot::ConstRefVector v_urdf, dg::sot::RefVector v_sot) |
| bool | velocity_urdf_to_sot (dynamicgraph::sot::ConstRefVector v_urdf, dynamicgraph::sot::RefVector v_sot) |
Variables | |
| const double | DEFAULT_MAX_CURRENT = 5 |
| max joint position tracking error [rad] More... | |
| const double | DEFAULT_MAX_DELTA_Q = 0.1 |
| const double | IMU_XYZ [3] = { -0.13, 0.0, 0.118} |
| max CURRENT (double in [0 Amp, 20 Amp]) More... | |
| const double | LEFT_FOOT_FORCE_SENSOR_MASS_PERCENTAGE = 0.65 |
| const double | LEFT_FOOT_FORCE_SENSOR_XYZ [3] = {0.0, 0.0, -0.0} |
| const double | LEFT_FOOT_SOLE_XYZ [3] = {0.0, 0.0, -0.107} |
| const double | LEFT_HAND_FORCE_SENSOR_MASS_PERCENTAGE = 0.75 |
| const double | LEFT_HAND_FORCE_SENSOR_XYZ [3] = {0.005, 0.0, -0.051} |
| const double | LEFT_HAND_FORCE_SENSOR_Z_ROTATION = -0.5 * M_PI |
| const double | LEFT_HAND_GRIPPER_XYZ [3] = {0.0, 0.0, 0.02025} |
| const double | RIGHT_FOOT_FORCE_SENSOR_MASS_PERCENTAGE = 0.65 |
| Percentage of mass of the link that is measured by the F/T sensors. More... | |
| const double | RIGHT_FOOT_FORCE_SENSOR_XYZ [3] = {0.0, 0.0, -0.0} |
| Position of the force/torque sensors w.r.t. the frame of the hosting link. More... | |
| const double | RIGHT_FOOT_SOLE_XYZ [3] = {0.0, 0.0, -0.107} |
| Position of the foot soles w.r.t. the frame of the foot. More... | |
| const double | RIGHT_HAND_FORCE_SENSOR_MASS_PERCENTAGE = 0.75 |
| const double | RIGHT_HAND_FORCE_SENSOR_XYZ [3] = {0.0, 0.0, -0.051} |
| const double | RIGHT_HAND_FORCE_SENSOR_Z_ROTATION = -0.5 * M_PI |
| Rotation angle around Z axis of the force/torque sensors w.r.t. the frame of the hosting link. More... | |
| const double | RIGHT_HAND_GRIPPER_XYZ [3] = {0.0, 0.0, -0.02875} |
| Position of the hand grippers w.r.t. the frame of the hand. More... | |
| enum ForceID |
| Enumerator | |
|---|---|
| FORCE_ID_RIGHT_FOOT | |
| FORCE_ID_LEFT_FOOT | |
| FORCE_ID_RIGHT_HAND | |
| FORCE_ID_LEFT_HAND | |
Definition at line 246 of file talos-common.hh.
| bool dynamicgraph::sot::torque_control::base_se3_to_sot | ( | dg::sot::ConstRefVector | pos, |
| dg::sot::ConstRefMatrix | R, | ||
| dg::sot::RefVector | q_sot | ||
| ) |
Definition at line 17 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::base_se3_to_sot | ( | dynamicgraph::sot::ConstRefVector | pos, |
| dynamicgraph::sot::ConstRefMatrix | R, | ||
| dynamicgraph::sot::RefVector | q_sot | ||
| ) |
| bool dynamicgraph::sot::torque_control::base_sot_to_urdf | ( | dg::sot::ConstRefVector | q_sot, |
| dg::sot::RefVector | q_urdf | ||
| ) |
Definition at line 55 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::base_sot_to_urdf | ( | dynamicgraph::sot::ConstRefVector | q_sot, |
| dynamicgraph::sot::RefVector | q_urdf | ||
| ) |
| bool dynamicgraph::sot::torque_control::base_urdf_to_sot | ( | dg::sot::ConstRefVector | q_urdf, |
| dg::sot::RefVector | q_sot | ||
| ) |
Definition at line 43 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::base_urdf_to_sot | ( | dynamicgraph::sot::ConstRefVector | q_urdf, |
| dynamicgraph::sot::RefVector | q_sot | ||
| ) |
| bool dynamicgraph::sot::torque_control::config_sot_to_urdf | ( | dg::sot::ConstRefVector | q_sot, |
| dg::sot::RefVector | q_urdf | ||
| ) |
Definition at line 147 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::config_sot_to_urdf | ( | dynamicgraph::sot::ConstRefVector | q_sot, |
| dynamicgraph::sot::RefVector | q_urdf | ||
| ) |
| bool dynamicgraph::sot::torque_control::config_urdf_to_sot | ( | dg::sot::ConstRefVector | q_urdf, |
| dg::sot::RefVector | q_sot | ||
| ) |
Definition at line 78 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::config_urdf_to_sot | ( | dynamicgraph::sot::ConstRefVector | q_urdf, |
| dynamicgraph::sot::RefVector | q_sot | ||
| ) |
| bool dynamicgraph::sot::torque_control::joints_sot_to_urdf | ( | dynamicgraph::sot::ConstRefVector | q_sot, |
| dynamicgraph::sot::RefVector | q_urdf | ||
| ) |
| bool dynamicgraph::sot::torque_control::joints_sot_to_urdf | ( | dg::sot::ConstRefVector | q_sot, |
| dg::sot::RefVector | q_urdf | ||
| ) |
Definition at line 352 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::joints_urdf_to_sot | ( | dg::sot::ConstRefVector | q_urdf, |
| dg::sot::RefVector | q_sot | ||
| ) |
Definition at line 310 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::joints_urdf_to_sot | ( | dynamicgraph::sot::ConstRefVector | q_urdf, |
| dynamicgraph::sot::RefVector | q_sot | ||
| ) |
| bool dynamicgraph::sot::torque_control::velocity_sot_to_urdf | ( | dg::sot::ConstRefVector | v_sot, |
| dg::sot::RefVector | v_urdf | ||
| ) |
Definition at line 259 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::velocity_sot_to_urdf | ( | dynamicgraph::sot::ConstRefVector | v_sot, |
| dynamicgraph::sot::RefVector | v_urdf | ||
| ) |
| bool dynamicgraph::sot::torque_control::velocity_urdf_to_sot | ( | dg::sot::ConstRefVector | v_urdf, |
| dg::sot::RefVector | v_sot | ||
| ) |
Definition at line 208 of file talos-common.cpp.
| bool dynamicgraph::sot::torque_control::velocity_urdf_to_sot | ( | dynamicgraph::sot::ConstRefVector | v_urdf, |
| dynamicgraph::sot::RefVector | v_sot | ||
| ) |
| const double DEFAULT_MAX_CURRENT = 5 |
max joint position tracking error [rad]
Definition at line 46 of file talos-common.hh.
| const double DEFAULT_MAX_DELTA_Q = 0.1 |
Definition at line 44 of file talos-common.hh.
| const double IMU_XYZ[3] = { -0.13, 0.0, 0.118} |
max CURRENT (double in [0 Amp, 20 Amp])
Position of the IMU w.r.t. the frame of the hosting link (torso)
Definition at line 62 of file talos-common.hh.
| const double LEFT_FOOT_FORCE_SENSOR_MASS_PERCENTAGE = 0.65 |
Definition at line 84 of file talos-common.hh.
| const double LEFT_FOOT_FORCE_SENSOR_XYZ[3] = {0.0, 0.0, -0.0} |
Definition at line 66 of file talos-common.hh.
| const double LEFT_FOOT_SOLE_XYZ[3] = {0.0, 0.0, -0.107} |
Definition at line 76 of file talos-common.hh.
| const double LEFT_HAND_FORCE_SENSOR_MASS_PERCENTAGE = 0.75 |
Definition at line 86 of file talos-common.hh.
| const double LEFT_HAND_FORCE_SENSOR_XYZ[3] = {0.005, 0.0, -0.051} |
Definition at line 68 of file talos-common.hh.
| const double LEFT_HAND_FORCE_SENSOR_Z_ROTATION = -0.5 * M_PI |
Definition at line 72 of file talos-common.hh.
| const double LEFT_HAND_GRIPPER_XYZ[3] = {0.0, 0.0, 0.02025} |
Definition at line 80 of file talos-common.hh.
| const double RIGHT_FOOT_FORCE_SENSOR_MASS_PERCENTAGE = 0.65 |
Percentage of mass of the link that is measured by the F/T sensors.
Definition at line 83 of file talos-common.hh.
| const double RIGHT_FOOT_FORCE_SENSOR_XYZ[3] = {0.0, 0.0, -0.0} |
Position of the force/torque sensors w.r.t. the frame of the hosting link.
Definition at line 65 of file talos-common.hh.
| const double RIGHT_FOOT_SOLE_XYZ[3] = {0.0, 0.0, -0.107} |
Position of the foot soles w.r.t. the frame of the foot.
Definition at line 75 of file talos-common.hh.
| const double RIGHT_HAND_FORCE_SENSOR_MASS_PERCENTAGE = 0.75 |
Definition at line 85 of file talos-common.hh.
| const double RIGHT_HAND_FORCE_SENSOR_XYZ[3] = {0.0, 0.0, -0.051} |
Definition at line 67 of file talos-common.hh.
| const double RIGHT_HAND_FORCE_SENSOR_Z_ROTATION = -0.5 * M_PI |
Rotation angle around Z axis of the force/torque sensors w.r.t. the frame of the hosting link.
Definition at line 71 of file talos-common.hh.
| const double RIGHT_HAND_GRIPPER_XYZ[3] = {0.0, 0.0, -0.02875} |
Position of the hand grippers w.r.t. the frame of the hand.
Definition at line 79 of file talos-common.hh.