#include <arm.hpp>
|
| bool | addPlugin (std::unique_ptr< plugin::Plugin > plugin) |
| |
| template<class T > |
| std::weak_ptr< plugin::Plugin > | getPluginByType () |
| |
| std::weak_ptr< plugin::Plugin > | getPluginByName (const std::string &name) |
| |
| bool | loadGains (const std::string &gains_file) |
| |
| void | setEndEffector (std::shared_ptr< arm::EndEffectorBase > ee) |
| |
| size_t | size () const |
| |
| const Group & | group () const |
| |
| Group & | group () |
| |
| const robot_model::RobotModel & | robotModel () const |
| |
| robot_model::RobotModel & | robotModel () |
| |
| const trajectory::Trajectory * | trajectory () const |
| |
| const EndEffectorBase * | endEffector () const |
| |
| EndEffectorBase * | endEffector () |
| |
| const GroupCommand & | pendingCommand () const |
| |
| GroupCommand & | pendingCommand () |
| |
| const GroupFeedback & | lastFeedback () const |
| |
| bool | update () |
| |
| bool | send () |
| |
| void | setGoal (const Goal &goal) |
| |
| void | currentState (Eigen::VectorXd &positions, Eigen::VectorXd &velocities, Eigen::VectorXd &accelerations) const |
| |
| template<typename T > |
| void | setAuxState (const T &aux_state) |
| |
| double | goalProgress () const |
| |
| bool | atGoal () const |
| |
| void | cancelGoal () |
| |
| void | setJointLimits (const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions) |
| |
| void | clearJointLimits () |
| |
| Eigen::Vector3d | FK (const Eigen::VectorXd &positions) const |
| |
| void | FK (const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const |
| |
| void | FK (const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const |
| |
| Eigen::VectorXd | solveIK (const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const |
| |
| Eigen::VectorXd | solveIK (const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const |
| |
| Eigen::VectorXd | solveIK (const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Matrix3d &orientation) const |
| |
◆ create() [1/4]
| std::unique_ptr< Arm > hebi::arm::Arm::create |
( |
const RobotConfig & |
config | ) |
|
|
static |
◆ create() [2/4]
◆ create() [3/4]
| std::unique_ptr< Arm > hebi::arm::Arm::create |
( |
const Params & |
params | ) |
|
|
static |
◆ create() [4/4]
| std::unique_ptr< Arm > hebi::arm::Arm::create |
( |
const Params & |
config, |
|
|
const Lookup & |
lookup |
|
) |
| |
|
static |
◆ addPlugin()
| bool hebi::arm::Arm::addPlugin |
( |
std::unique_ptr< plugin::Plugin > |
plugin | ) |
|
◆ getPluginByType()
◆ getPluginByName()
| std::weak_ptr< plugin::Plugin > hebi::arm::Arm::getPluginByName |
( |
const std::string & |
name | ) |
|
◆ loadGains()
| bool hebi::arm::Arm::loadGains |
( |
const std::string & |
gains_file | ) |
|
◆ setEndEffector()
◆ size()
| size_t hebi::arm::Arm::size |
( |
| ) |
const |
|
inline |
◆ group() [1/2]
| const Group& hebi::arm::Arm::group |
( |
| ) |
const |
|
inline |
◆ group() [2/2]
| Group& hebi::arm::Arm::group |
( |
| ) |
|
|
inline |
◆ robotModel() [1/2]
◆ robotModel() [2/2]
◆ trajectory()
◆ endEffector() [1/2]
◆ endEffector() [2/2]
◆ pendingCommand() [1/2]
| const GroupCommand& hebi::arm::Arm::pendingCommand |
( |
| ) |
const |
|
inline |
◆ pendingCommand() [2/2]
◆ lastFeedback()
◆ update()
| bool hebi::arm::Arm::update |
( |
| ) |
|
◆ send()
| bool hebi::arm::Arm::send |
( |
| ) |
|
◆ setGoal()
| void hebi::arm::Arm::setGoal |
( |
const Goal & |
goal | ) |
|
◆ currentState()
| void hebi::arm::Arm::currentState |
( |
Eigen::VectorXd & |
positions, |
|
|
Eigen::VectorXd & |
velocities, |
|
|
Eigen::VectorXd & |
accelerations |
|
) |
| const |
◆ setAuxState()
template<typename T >
| void hebi::arm::Arm::setAuxState |
( |
const T & |
aux_state | ) |
|
|
inline |
◆ goalProgress()
| double hebi::arm::Arm::goalProgress |
( |
| ) |
const |
◆ atGoal()
| bool hebi::arm::Arm::atGoal |
( |
| ) |
const |
|
inline |
◆ cancelGoal()
| void hebi::arm::Arm::cancelGoal |
( |
| ) |
|
◆ setJointLimits()
| void hebi::arm::Arm::setJointLimits |
( |
const Eigen::VectorXd & |
min_positions, |
|
|
const Eigen::VectorXd & |
max_positions |
|
) |
| |
|
inline |
◆ clearJointLimits()
| void hebi::arm::Arm::clearJointLimits |
( |
| ) |
|
|
inline |
◆ FK() [1/3]
| Eigen::Vector3d hebi::arm::Arm::FK |
( |
const Eigen::VectorXd & |
positions | ) |
const |
|
inline |
◆ FK() [2/3]
| void hebi::arm::Arm::FK |
( |
const Eigen::VectorXd & |
positions, |
|
|
Eigen::Vector3d & |
xyz_out, |
|
|
Eigen::Vector3d & |
tip_axis |
|
) |
| const |
|
inline |
◆ FK() [3/3]
| void hebi::arm::Arm::FK |
( |
const Eigen::VectorXd & |
positions, |
|
|
Eigen::Vector3d & |
xyz_out, |
|
|
Eigen::Matrix3d & |
orientation |
|
) |
| const |
|
inline |
◆ solveIK() [1/3]
| Eigen::VectorXd hebi::arm::Arm::solveIK |
( |
const Eigen::VectorXd & |
initial_positions, |
|
|
const Eigen::Vector3d & |
target_xyz |
|
) |
| const |
|
inline |
◆ solveIK() [2/3]
| Eigen::VectorXd hebi::arm::Arm::solveIK |
( |
const Eigen::VectorXd & |
initial_positions, |
|
|
const Eigen::Vector3d & |
target_xyz, |
|
|
const Eigen::Vector3d & |
end_tip |
|
) |
| const |
|
inline |
◆ solveIK() [3/3]
| Eigen::VectorXd hebi::arm::Arm::solveIK |
( |
const Eigen::VectorXd & |
initial_positions, |
|
|
const Eigen::Vector3d & |
target_xyz, |
|
|
const Eigen::Matrix3d & |
orientation |
|
) |
| const |
|
inline |
The documentation for this class was generated from the following files: