Joint Level Control
Public Member Functions | List of all members
SwingJoint Class Reference

This Packages the HallSensor class and Motor class together into a Hardware Interface. More...

#include <swing_joint.h>

Inheritance diagram for SwingJoint:
Inheritance graph
[legend]
Collaboration diagram for SwingJoint:
Collaboration graph
[legend]

Public Member Functions

 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. More...
 
 ~SwingJoint ()
 destructor of SwingJoint class
 
void read ()
 Reads the Angle of the HallSensor and weighs errors of read. More...
 
void write ()
 Writes a command position to the motors.
 
void calibrate ()
 Sets the zero angle of the hallsensor using an internal function

 
uint getErrorState ()
 Returns true if the sensor is in ERROR state, false otherwise. More...
 

Detailed Description

This Packages the HallSensor class and Motor class together into a Hardware Interface.

The class offers two types of interfaces, a joint state interface which reads the joint position from the HallSensor class and a effort interface with which feedback controllers can controll the torque of the robot. More information on hardware interfaces can be found here. It also offers a calibration function which calls the setZero method of the HallSensor. This is done to allow calibration via ROS services. Lastly it contains a function for reading out how many errors in a row the last read accesses had.

Constructor & Destructor Documentation

◆ SwingJoint()

SwingJoint::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.

double upper joint limit

Parameters
joint_namestring joint name
spi_devicestring file descriptor of spi device
spi_cs_iduint8_t id of sensor on multiplexer
spi_modeuint8_t mode of spi transfer: clock phase & polarity
spi_bitsuint8_t spi bits per word
spi_speeduint32_t spi transfer speed in Hz
spi_delayuint16_t delay in usec after last bit transfer, before device deselect.
can_namestring can name
can_iduint8_t can id
zero_pointdouble zero angle offset for sensor
error_command_positiondouble default motor position (current) if errors occur
spi_error_tresholduint upper limit for accumulated errors, till ERROR state is reached
mux_sel_pin_1uint16_t 1st selector pin for multiplexer
mux_sel_pin_2uint16_t 2nd selector pin for multiplexer
joint_min_posdouble lower joint limit

Member Function Documentation

◆ getErrorState()

uint SwingJoint::getErrorState ( )

Returns true if the sensor is in ERROR state, false otherwise.

Checks if the weighted sum of errors is greater than the error threshold.

◆ read()

void SwingJoint::read ( )

Reads the Angle of the HallSensor and weighs errors of read.

This function sets internal position variable for controller. It also reads the errors of the read access, and calculates a weighted sum of them. The sum dictates, whether the joint is in ERROR state, which is reached if: sum > spi_error_treshold


The documentation for this class was generated from the following files: