16 namespace experimental {
74 using clock = std::chrono::steady_clock;
75 static const clock::time_point start_time = clock::now();
76 return (std::chrono::duration<double>(clock::now() - start_time)).count();
82 static std::unique_ptr<Arm>
create(
const Params& params);
87 bool loadGains(
const std::string& gains_file);
181 auto aux_size = aux_state.size();
182 if (aux_state.size() > 0) {
185 aux_.resize(aux_size, 1);
187 for (
size_t i = 0; i < aux_size; i++) {
188 aux_(i, 0) = aux_state[i];
217 void setJointLimits(
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions) {
223 void clearJointLimits(
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions) {
228 Eigen::Vector3d
FK(
const Eigen::VectorXd& positions)
const {
233 void FK(
const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Vector3d& tip_axis)
const {
238 void FK(
const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Matrix3d& orientation)
const {
244 const Eigen::VectorXd& initial_positions,
245 const Eigen::Vector3d& target_xyz)
const {
252 const Eigen::VectorXd& initial_positions,
253 const Eigen::Vector3d& target_xyz,
254 const Eigen::Vector3d& end_tip)
const {
261 const Eigen::VectorXd& initial_positions,
262 const Eigen::Vector3d& target_xyz,
263 const Eigen::Matrix3d& orientation)
const {
269 Arm(std::function<
double()> get_current_time_s,
270 std::shared_ptr<Group>
group,
271 std::shared_ptr<robot_model::RobotModel> robot_model,
272 std::shared_ptr<EndEffectorBase> end_effector =
nullptr) :
285 Eigen::VectorXd
getAux(
double t)
const;
A list of Feedback objects that can be received from a Group of modules; the size() must match the nu...
Eigen::VectorXd solveIK6Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Matrix3d &orientation) const
const trajectory::Trajectory * trajectory() const
std::shared_ptr< robot_model::RobotModel > robot_model_
double trajectory_start_time_
Represents a group of physical HEBI modules, and allows Command, Feedback, and Info objects to be sen...
std::shared_ptr< robot_model::RobotModel > robot_model_
const robot_model::RobotModel & robotModel() const
void FK6Dof(const robot_model::RobotModel &robot_model, 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::Matrix3d &orientation) const
Eigen::VectorXd solveIK5Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const
void FK5Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
void clearJointLimits(const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const
std::shared_ptr< trajectory::Trajectory > trajectory_
void FK(const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
Eigen::VectorXd solveIK3Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
double control_frequency_
const GroupFeedback & lastFeedback() const
Represents a chain or tree of robot elements (rigid bodies and joints).
std::function< double()> get_current_time_s_
Eigen::Vector3d FK3Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions) const
void setJointLimits(const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
const Group & group() const
static std::unique_ptr< Arm > create(const Params ¶ms)
const EndEffectorBase * endEffector() const
std::shared_ptr< EndEffectorBase > end_effector_
void FK(const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const
const GroupCommand & pendingCommand() const
double goalProgress() const
A list of Command objects appropriate for sending to a Group of modules; the size() must match the nu...
std::shared_ptr< Group > group_
void setAuxState(const T &aux_state)
std::function< double()> get_current_time_s_
bool loadGains(const std::string &gains_file)
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
Represents a smooth trajectory through a set of waypoints.
GroupCommand & pendingCommand()
void setGoal(const Goal &goal)
Eigen::Vector3d FK(const Eigen::VectorXd &positions) const
std::vector< std::string > names_
hebi::GroupFeedback feedback_
std::vector< std::string > families_
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)
Eigen::VectorXd aux_times_
hebi::GroupCommand command_
void setJointLimits(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
std::shared_ptr< EndEffectorBase > end_effector_
internal::KinematicsHelper kinematics_helper_
Eigen::VectorXd getAux(double t) const