#include <arm.hpp>
|
| bool | atGoal () const |
| |
| void | cancelGoal () |
| |
| void | clearJointLimits (const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions) |
| |
| const EndEffectorBase * | endEffector () const |
| |
| 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 |
| |
| double | goalProgress () const |
| |
| const Group & | group () const |
| |
| const GroupFeedback & | lastFeedback () const |
| |
| bool | loadGains (const std::string &gains_file) |
| |
| GroupCommand & | pendingCommand () |
| |
| const GroupCommand & | pendingCommand () const |
| |
| const robot_model::RobotModel & | robotModel () const |
| |
| bool | send () |
| |
| template<typename T > |
| void | setAuxState (const T &aux_state) |
| |
| void | setGoal (const Goal &goal) |
| |
| void | setJointLimits (const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions) |
| |
| size_t | size () 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 |
| |
| const trajectory::Trajectory * | trajectory () const |
| |
| bool | update () |
| |
Definition at line 41 of file arm.hpp.
◆ Arm()
| hebi::experimental::arm::Arm::Arm |
( |
std::function< double()> |
get_current_time_s, |
|
|
std::shared_ptr< Group > |
group, |
|
|
std::shared_ptr< robot_model::RobotModel > |
robot_model, |
|
|
std::shared_ptr< EndEffectorBase > |
end_effector = nullptr |
|
) |
| |
|
inlineprivate |
◆ atGoal()
| bool hebi::experimental::arm::Arm::atGoal |
( |
| ) |
const |
|
inline |
◆ cancelGoal()
| void hebi::experimental::arm::Arm::cancelGoal |
( |
| ) |
|
◆ clearJointLimits()
| void hebi::experimental::arm::Arm::clearJointLimits |
( |
const Eigen::VectorXd & |
min_positions, |
|
|
const Eigen::VectorXd & |
max_positions |
|
) |
| |
|
inline |
◆ create()
| std::unique_ptr< Arm > hebi::experimental::arm::Arm::create |
( |
const Params & |
params | ) |
|
|
static |
◆ endEffector()
◆ FK() [1/3]
| Eigen::Vector3d hebi::experimental::arm::Arm::FK |
( |
const Eigen::VectorXd & |
positions | ) |
const |
|
inline |
◆ FK() [2/3]
| void hebi::experimental::arm::Arm::FK |
( |
const Eigen::VectorXd & |
positions, |
|
|
Eigen::Vector3d & |
xyz_out, |
|
|
Eigen::Vector3d & |
tip_axis |
|
) |
| const |
|
inline |
◆ FK() [3/3]
| void hebi::experimental::arm::Arm::FK |
( |
const Eigen::VectorXd & |
positions, |
|
|
Eigen::Vector3d & |
xyz_out, |
|
|
Eigen::Matrix3d & |
orientation |
|
) |
| const |
|
inline |
◆ getAux()
| Eigen::VectorXd hebi::experimental::arm::Arm::getAux |
( |
double |
t | ) |
const |
|
private |
◆ goalProgress()
| double hebi::experimental::arm::Arm::goalProgress |
( |
| ) |
const |
◆ group()
| const Group& hebi::experimental::arm::Arm::group |
( |
| ) |
const |
|
inline |
◆ lastFeedback()
| const GroupFeedback& hebi::experimental::arm::Arm::lastFeedback |
( |
| ) |
const |
|
inline |
◆ loadGains()
| bool hebi::experimental::arm::Arm::loadGains |
( |
const std::string & |
gains_file | ) |
|
◆ pendingCommand() [1/2]
| GroupCommand& hebi::experimental::arm::Arm::pendingCommand |
( |
| ) |
|
|
inline |
◆ pendingCommand() [2/2]
| const GroupCommand& hebi::experimental::arm::Arm::pendingCommand |
( |
| ) |
const |
|
inline |
◆ robotModel()
◆ send()
| bool hebi::experimental::arm::Arm::send |
( |
| ) |
|
◆ setAuxState()
template<typename T >
| void hebi::experimental::arm::Arm::setAuxState |
( |
const T & |
aux_state | ) |
|
|
inline |
◆ setGoal()
| void hebi::experimental::arm::Arm::setGoal |
( |
const Goal & |
goal | ) |
|
◆ setJointLimits()
| void hebi::experimental::arm::Arm::setJointLimits |
( |
const Eigen::VectorXd & |
min_positions, |
|
|
const Eigen::VectorXd & |
max_positions |
|
) |
| |
|
inline |
◆ size()
| size_t hebi::experimental::arm::Arm::size |
( |
| ) |
const |
|
inline |
◆ solveIK() [1/3]
| Eigen::VectorXd hebi::experimental::arm::Arm::solveIK |
( |
const Eigen::VectorXd & |
initial_positions, |
|
|
const Eigen::Vector3d & |
target_xyz |
|
) |
| const |
|
inline |
◆ solveIK() [2/3]
| Eigen::VectorXd hebi::experimental::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::experimental::arm::Arm::solveIK |
( |
const Eigen::VectorXd & |
initial_positions, |
|
|
const Eigen::Vector3d & |
target_xyz, |
|
|
const Eigen::Matrix3d & |
orientation |
|
) |
| const |
|
inline |
◆ trajectory()
◆ update()
| bool hebi::experimental::arm::Arm::update |
( |
| ) |
|
◆ accel_
| Eigen::VectorXd hebi::experimental::arm::Arm::accel_ |
|
private |
◆ aux_
| Eigen::MatrixXd hebi::experimental::arm::Arm::aux_ |
|
private |
◆ aux_times_
| Eigen::VectorXd hebi::experimental::arm::Arm::aux_times_ |
|
private |
◆ command_
◆ end_effector_
| std::shared_ptr<EndEffectorBase> hebi::experimental::arm::Arm::end_effector_ |
|
private |
◆ feedback_
◆ get_current_time_s_
| std::function<double()> hebi::experimental::arm::Arm::get_current_time_s_ |
|
private |
◆ group_
| std::shared_ptr<Group> hebi::experimental::arm::Arm::group_ |
|
private |
◆ kinematics_helper_
◆ last_time_
| double hebi::experimental::arm::Arm::last_time_ |
|
private |
◆ masses_
| Eigen::VectorXd hebi::experimental::arm::Arm::masses_ |
|
private |
◆ pos_
| Eigen::VectorXd hebi::experimental::arm::Arm::pos_ |
|
private |
◆ robot_model_
◆ trajectory_
◆ trajectory_start_time_
| double hebi::experimental::arm::Arm::trajectory_start_time_ { std::numeric_limits<double>::quiet_NaN() } |
|
private |
◆ vel_
| Eigen::VectorXd hebi::experimental::arm::Arm::vel_ |
|
private |
The documentation for this class was generated from the following files: