Struct RobotOutput

Nested Relationships

Nested Types

Struct Documentation

struct RobotOutput

Robot output.

Public Members

struct trossen_arm::RobotOutput::Joint joint
struct trossen_arm::RobotOutput::Cartesian cartesian
struct Cartesian

Outputs in Cartesian space.

Public Members

std::array<double, 6> positions

Spatial position of the end effector frame measured in the base frame in m and rad.

Note

The first 3 elements are the translation and the last 3 elements are the angle-axis representation of the rotation

std::array<double, 6> velocities

Spatial velocity of the end effector frame with respect to the base frame measured in the base frame in m/s and rad/s.

Note

The first 3 elements are the linear velocity and the last 3 elements are the angular velocity

std::array<double, 6> accelerations

Spatial acceleration of the end effector frame with respect to the base frame measured in the base frame in m/s^2 and rad/s^2.

Note

The first 3 elements are the linear acceleration and the last 3 elements are the angular acceleration

std::array<double, 6> external_efforts

Spatial external efforts applied to the end effector frame measured in the base frame in N and Nm.

Note

The first 3 elements are the force and the last 3 elements are the torque

Note

All external efforts are assumed to be applied at the end effector frame

struct Joint

Outputs in joint space.

Public Members

struct trossen_arm::RobotOutput::Joint::All all
struct trossen_arm::RobotOutput::Joint::Arm arm
struct trossen_arm::RobotOutput::Joint::Gripper gripper
struct All

Outputs of all joints.

Public Members

std::vector<double> positions

Positions in rad for arm joints and m for the gripper joint.

std::vector<double> velocities

Velocities in rad/s for arm joints and m/s for the gripper joint.

std::vector<double> accelerations

Accelerations in rad/s^2 for arm joints and m/s^2 for the gripper joint.

std::vector<double> efforts

Efforts in Nm for arm joints and N for the gripper joint.

std::vector<double> external_efforts

External efforts in Nm for arm joints and N for the gripper joint.

std::vector<double> compensation_efforts

Compensation efforts in Nm for arm joints and N for the gripper joint.

std::vector<double> rotor_temperatures

Rotor temperatures in C.

std::vector<double> driver_temperatures

Driver temperatures in C.

struct Arm

Outputs of the arm joints.

Public Members

std::vector<double> positions

Positions in rad.

std::vector<double> velocities

Velocities in rad/s.

std::vector<double> accelerations

Accelerations in rad/s^2.

std::vector<double> efforts

Efforts in Nm.

std::vector<double> external_efforts

External efforts in Nm.

std::vector<double> compensation_efforts

Compensation efforts in Nm.

std::vector<double> rotor_temperatures

Rotor temperatures in C.

std::vector<double> driver_temperatures

Driver temperatures in C.

struct Gripper

Outputs of the gripper joint.

Public Members

double position

Position in m.

double velocity

Velocity in m/s.

double acceleration

Acceleration in m/s^2.

double effort

Effort in N.

double external_effort

External effort in N.

double compensation_effort

Compensation effort in N.

double rotor_temperature

Rotor temperature in C.

double driver_temperature

Driver temperature in C.