7 #include <hardware_interface/joint_command_interface.h>
8 #include <hardware_interface/joint_state_interface.h>
9 #include <hardware_interface/robot_hw.h>
11 #include <joint_limits_interface/joint_limits.h>
12 #include <joint_limits_interface/joint_limits_interface.h>
14 #include <joint_limits_interface/joint_limits_rosparam.h>
16 #include "joint_level_control/hall_sensor/hall_sensor.h"
17 #include "joint_level_control/motor/motor.h"
35 const std::string& joint_name,
36 const std::string& spi_device,
42 const std::string& can_name,
45 double error_command_position,
46 uint spi_error_treshold,
47 uint16_t mux_sel_pin_1,
48 uint16_t mux_sel_pin_2,
50 double joint_max_pos);
78 hardware_interface::JointStateInterface joint_state_interface_;
79 hardware_interface::EffortJointInterface effort_joint_interface_;
81 joint_limits_interface::JointLimits limits;
82 joint_limits_interface::EffortJointSaturationInterface effortJointSaturationInterface;
83 joint_limits_interface::PositionJointSaturationInterface positionJointSaturationInterface;
88 double command_position_;
89 double error_command_position_;
92 double joint_min_pos_;
93 double joint_max_pos_;
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