Class ServoBusInterface

Inheritance Relationships

Base Type

Class Documentation

class bitbots_ros_control::ServoBusInterface : public bitbots_ros_control::HardwareInterface

Public Functions

explicit ServoBusInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver> &driver, std::vector<std::tuple<int, std::string, float, float, std::string>> servos)
virtual bool init()
virtual void read(const rclcpp::Time &t, const rclcpp::Duration &dt)
virtual void write(const rclcpp::Time &t, const rclcpp::Duration &dt)
virtual void restoreAfterPowerCycle()
bool loadDynamixels()
bool writeROMRAM(bool first_time)
void syncWritePWM()
void switchDynamixelControlMode()
diagnostic_msgs::msg::DiagnosticStatus createServoDiagMsg(int id, char level, std::string message, std::map<std::string, std::string> map, std::string name)
void processVte(bool success)
void writeTorque(bool enabled)
void writeTorqueForServos(std::vector<int32_t> torque)
bool syncReadPositions()
bool syncReadVelocities()
bool syncReadEfforts()
bool syncReadPWMs()
bool syncReadAll()
bool syncReadVoltageAndTemp()
bool syncReadError()
void syncWritePosition()
void syncWriteVelocity()
void syncWriteProfileVelocity()
void syncWriteCurrent()
void syncWriteProfileAcceleration()

Public Members

bool goal_torque_
bool current_torque_
rclcpp::Node::SharedPtr nh_
std::vector<int32_t> data_sync_read_positions_
std::vector<int32_t> data_sync_read_velocities_
std::vector<int32_t> data_sync_read_efforts_
std::vector<int32_t> data_sync_read_pwms_
std::vector<int32_t> data_sync_read_error_
std::vector<int32_t> sync_write_goal_position_
std::vector<int32_t> sync_write_goal_velocity_
std::vector<int32_t> sync_write_profile_velocity_
std::vector<int32_t> sync_write_profile_acceleration_
std::vector<int32_t> sync_write_goal_current_
std::vector<int32_t> sync_write_goal_pwm_
std::vector<uint8_t> sync_read_all_data_
bool first_cycle_
bool lost_servo_connection_
ControlMode control_mode_
bool switch_individual_torque_
std::shared_ptr<DynamixelDriver> driver_
std::vector<std::tuple<int, std::string, float, float, std::string>> servos_
int joint_count_
std::vector<int32_t> goal_torque_individual_
std::vector<std::string> joint_names_
std::vector<uint8_t> joint_ids_
std::vector<double> joint_mounting_offsets_
std::vector<double> joint_offsets_
std::vector<std::string> joint_groups_
std::vector<double> goal_position_
std::vector<double> goal_effort_
std::vector<double> goal_velocity_
std::vector<double> goal_acceleration_
std::vector<double> last_goal_position_
std::vector<double> last_goal_effort_
std::vector<double> last_goal_velocity_
std::vector<double> last_goal_acceleration_
bool read_position_
bool read_velocity_
bool read_effort_
bool read_pwm_
bool read_volt_temp_
std::vector<double> current_position_
std::vector<double> current_velocity_
std::vector<double> current_effort_
std::vector<double> current_pwm_
std::vector<double> current_input_voltage_
std::vector<double> current_temperature_
std::vector<uint8_t> current_error_
int read_vt_counter_
int vt_update_rate_
double warn_temp_
double warn_volt_
bool torqueless_mode_
int reading_errors_
int reading_successes_
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diagnostic_pub_
rclcpp::Publisher<bitbots_msgs::msg::Audio>::SharedPtr speak_pub_