Joint Level Control
swing_joint.h
1 #ifndef SWING_JOINT_H
2 #define SWING_JOINT_H
3 
4 
5 #include <string>
6 
7 #include <hardware_interface/joint_command_interface.h>
8 #include <hardware_interface/joint_state_interface.h>
9 #include <hardware_interface/robot_hw.h>
10 
11 #include <joint_limits_interface/joint_limits.h>
12 #include <joint_limits_interface/joint_limits_interface.h>
13 //#include <joint_limits_interface/joint_limits_urdf.h>
14 #include <joint_limits_interface/joint_limits_rosparam.h>
15 
16 #include "joint_level_control/hall_sensor/hall_sensor.h"
17 #include "joint_level_control/motor/motor.h"
18 
19 
28 class SwingJoint : public hardware_interface::RobotHW
29 {
30 public:
34  SwingJoint(
35  const std::string& joint_name,
36  const std::string& spi_device,
37  uint8_t spi_cs_id,
38  uint8_t spi_mode,
39  uint8_t spi_bits,
40  uint32_t spi_speed,
41  uint16_t spi_delay,
42  const std::string& can_name,
43  uint8_t can_id,
44  double zero_point,
45  double error_command_position,
46  uint spi_error_treshold,
47  uint16_t mux_sel_pin_1,
48  uint16_t mux_sel_pin_2,
49  double joint_min_pos,
50  double joint_max_pos);
51 
52  ~SwingJoint();
53 
61  void read();
65  void write();
69  void calibrate();
75  uint getErrorState();
76 
77 private:
78  hardware_interface::JointStateInterface joint_state_interface_;
79  hardware_interface::EffortJointInterface effort_joint_interface_;
80 
81  joint_limits_interface::JointLimits limits;
82  joint_limits_interface::EffortJointSaturationInterface effortJointSaturationInterface;
83  joint_limits_interface::PositionJointSaturationInterface positionJointSaturationInterface;
84 
85  double position_;
86  double velocity_;
87  double effort_;
88  double command_position_;
89  double error_command_position_; // default value for cmd_pos if errors occur
90  uint error_state_; // current error state of the joint. 0: OK, otherwise #error_state errors occured in a row
91  uint error_limit_; // max #errors in a row until ERROR state is reached
92  double joint_min_pos_; // joint position limits
93  double joint_max_pos_;
94 
95  Motor motor_;
96  HallSensor hall_sensor_;
97 
98  ros::NodeHandle nh_;
99 };
100 
101 
102 #endif
This class abstracts the communication with the sensors measuring the state of the swingjoints.
Definition: hall_sensor.h:30
This class abstracts the communication with the motorcontrollers (currently Hacker Herkules 5 BLDC).
Definition: motor.h:15
This Packages the HallSensor class and Motor class together into a Hardware Interface.
Definition: swing_joint.h:29
~SwingJoint()
destructor of SwingJoint class
Definition: swing_joint.cpp:50
void read()
Reads the Angle of the HallSensor and weighs errors of read.
Definition: swing_joint.cpp:55
void write()
Writes a command position to the motors.
Definition: swing_joint.cpp:119
void calibrate()
Sets the zero angle of the hallsensor using an internal function
Definition: swing_joint.cpp:129
SwingJoint(const std::string &joint_name, const std::string &spi_device, uint8_t spi_cs_id, uint8_t spi_mode, uint8_t spi_bits, uint32_t spi_speed, uint16_t spi_delay, const std::string &can_name, uint8_t can_id, double zero_point, double error_command_position, uint spi_error_treshold, uint16_t mux_sel_pin_1, uint16_t mux_sel_pin_2, double joint_min_pos, double joint_max_pos)
Constructor of the SwingJoint class.
Definition: swing_joint.cpp:4
uint getErrorState()
Returns true if the sensor is in ERROR state, false otherwise.
Definition: swing_joint.cpp:134