42  explicit ElbowState(
const std::array<double, 2> &elbow_state)
 
   43      : joint_3_pos_(elbow_state[0]), joint_4_flip_([&]() -> std::optional<
FlipDirection> {
 
   44          if (elbow_state[1] < 0.0) {
 
   46          } 
else if (elbow_state[1] == 0.0) {
 
 
   63  [[nodiscard]] 
inline std::array<double, 2> 
to_array(
 
   65    return {joint_3_pos_, 
static_cast<double>(joint_4_flip_.value_or(default_flip_direction))};
 
 
   71  [[nodiscard]] 
inline double joint_3_pos()
 const { 
return joint_3_pos_; }
 
   76  [[nodiscard]] 
inline std::optional<FlipDirection> 
joint_4_flip()
 const { 
return joint_4_flip_; }
 
   81  double joint_3_pos_{0.0};
 
   82  std::optional<FlipDirection> joint_4_flip_{std::nullopt};
 
 
Elbow state of the robot.
Definition elbow_state.hpp:24
 
ElbowState(const std::array< double, 2 > &elbow_state)
Construct an elbow state from an array containing joint position and flip direction.
Definition elbow_state.hpp:42
 
friend std::ostream & operator<<(std::ostream &os, const ElbowState &elbow_state)
Definition elbow_state.cpp:7
 
std::array< double, 2 > to_array(FlipDirection default_flip_direction=FlipDirection::kNegative) const
Get the joint position and flip direction as an array.
Definition elbow_state.hpp:63
 
double joint_3_pos() const
The position of the 3rd joint.
Definition elbow_state.hpp:71
 
std::optional< FlipDirection > joint_4_flip() const
The flip direction of the 4th joint.
Definition elbow_state.hpp:76
 
ElbowState(double joint_3_pos, std::optional< FlipDirection > joint_4_flip=std::nullopt)
Construct an elbow state with the given joint position and optional flip direction.
Definition elbow_state.hpp:33
 
ElbowState(const ElbowState &)=default
 
Definition dynamics_limit.cpp:8
 
std::ostream & operator<<(std::ostream &os, const DynamicsLimit< Vector7d > &limit)
Definition dynamics_limit.cpp:47
 
FlipDirection
Flip direction of a joint.
Definition elbow_state.hpp:12