Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
TmcCoeMotor Class Reference

#include <tmc_coe_motor.h>

Inheritance diagram for TmcCoeMotor:
Inheritance graph
[legend]

Public Member Functions

virtual void init ()
 
 TmcCoeMotor (ros::NodeHandle *p_nh, TmcCoeInterpreter *p_tmc_coe_interpreter, uint8_t slave_number, uint8_t motor_number)
 
virtual ~TmcCoeMotor ()
 

Protected Member Functions

virtual void cmdAbsPosCallback (const std_msgs::Int32 msg)
 
virtual void cmdRelPosCallback (const std_msgs::Int32 msg)
 
virtual void cmdVelCallback (const geometry_msgs::Twist &msg)
 
void initPublisher ()
 
virtual void initSubscriber ()
 
virtual void rosPublishTmcCoeInfo (const ros::TimerEvent &event)
 

Protected Attributes

std::string frame_id_
 
uint8_t motor_number_
 
ros::NodeHandlep_nh_
 
TmcCoeInterpreterp_tmc_coe_interpreter_
 
float param_add_ratio_pos_
 
float param_add_ratio_trq_
 
float param_add_ratio_vel_
 
bool param_en_pub_tmc_coe_info_
 
std::string param_interface_name_
 
bool param_pub_actual_pos_
 
bool param_pub_actual_trq_
 
bool param_pub_actual_vel_
 
float param_pub_rate_tmc_coe_info_
 
int param_SDO_PDO_retries_
 
std::string param_tmc_cmd_abspos_topic_
 
std::string param_tmc_cmd_relpos_topic_
 
std::string param_tmc_cmd_trq_topic_
 
std::string param_tmc_cmd_vel_topic_
 
std::string param_tmc_coe_info_topic_
 
float param_wheel_diameter_
 
std::string s_namespace_
 
std::string s_node_name_
 
uint32_t seq_ctr_
 
uint8_t slave_number_
 
ros::Timer timer_callback_
 
ros::Subscriber tmc_cmd_abspos_sub_
 
ros::Subscriber tmc_cmd_relpos_sub_
 
ros::Subscriber tmc_cmd_vel_sub_
 
adi_tmc_coe::TmcCoeInfo tmc_coe_info_msg_
 
ros::Publisher tmc_coe_info_pub_
 

Private Member Functions

void initParams ()
 

Detailed Description

Definition at line 47 of file tmc_coe_motor.h.

Constructor & Destructor Documentation

◆ TmcCoeMotor()

TmcCoeMotor::TmcCoeMotor ( ros::NodeHandle p_nh,
TmcCoeInterpreter p_tmc_coe_interpreter,
uint8_t  slave_number,
uint8_t  motor_number 
)

Copyright (c) 2023-2024 Analog Devices, Inc. All Rights Reserved. This software is proprietary to Analog Devices, Inc. and its licensors.

Definition at line 11 of file tmc_coe_motor.cpp.

◆ ~TmcCoeMotor()

TmcCoeMotor::~TmcCoeMotor ( )
virtual

Definition at line 24 of file tmc_coe_motor.cpp.

Member Function Documentation

◆ cmdAbsPosCallback()

void TmcCoeMotor::cmdAbsPosCallback ( const std_msgs::Int32  msg)
protectedvirtual

Reimplemented in TmcCoeBLDCMotor, and TmcCoeStepperMotor.

Definition at line 383 of file tmc_coe_motor.cpp.

◆ cmdRelPosCallback()

void TmcCoeMotor::cmdRelPosCallback ( const std_msgs::Int32  msg)
protectedvirtual

Reimplemented in TmcCoeBLDCMotor, and TmcCoeStepperMotor.

Definition at line 436 of file tmc_coe_motor.cpp.

◆ cmdVelCallback()

void TmcCoeMotor::cmdVelCallback ( const geometry_msgs::Twist &  msg)
protectedvirtual

Reimplemented in TmcCoeBLDCMotor, and TmcCoeStepperMotor.

Definition at line 339 of file tmc_coe_motor.cpp.

◆ init()

void TmcCoeMotor::init ( )
virtual

Reimplemented in TmcCoeBLDCMotor, and TmcCoeStepperMotor.

Definition at line 33 of file tmc_coe_motor.cpp.

◆ initParams()

void TmcCoeMotor::initParams ( )
private

Definition at line 47 of file tmc_coe_motor.cpp.

◆ initPublisher()

void TmcCoeMotor::initPublisher ( )
protected

Definition at line 237 of file tmc_coe_motor.cpp.

◆ initSubscriber()

void TmcCoeMotor::initSubscriber ( )
protectedvirtual

Reimplemented in TmcCoeBLDCMotor, and TmcCoeStepperMotor.

Definition at line 329 of file tmc_coe_motor.cpp.

◆ rosPublishTmcCoeInfo()

void TmcCoeMotor::rosPublishTmcCoeInfo ( const ros::TimerEvent event)
protectedvirtual

Reimplemented in TmcCoeBLDCMotor, and TmcCoeStepperMotor.

Definition at line 276 of file tmc_coe_motor.cpp.

Member Data Documentation

◆ frame_id_

std::string TmcCoeMotor::frame_id_
protected

Definition at line 59 of file tmc_coe_motor.h.

◆ motor_number_

uint8_t TmcCoeMotor::motor_number_
protected

Definition at line 73 of file tmc_coe_motor.h.

◆ p_nh_

ros::NodeHandle* TmcCoeMotor::p_nh_
protected

Definition at line 92 of file tmc_coe_motor.h.

◆ p_tmc_coe_interpreter_

TmcCoeInterpreter* TmcCoeMotor::p_tmc_coe_interpreter_
protected

Definition at line 93 of file tmc_coe_motor.h.

◆ param_add_ratio_pos_

float TmcCoeMotor::param_add_ratio_pos_
protected

Definition at line 87 of file tmc_coe_motor.h.

◆ param_add_ratio_trq_

float TmcCoeMotor::param_add_ratio_trq_
protected

Definition at line 88 of file tmc_coe_motor.h.

◆ param_add_ratio_vel_

float TmcCoeMotor::param_add_ratio_vel_
protected

Definition at line 86 of file tmc_coe_motor.h.

◆ param_en_pub_tmc_coe_info_

bool TmcCoeMotor::param_en_pub_tmc_coe_info_
protected

Definition at line 76 of file tmc_coe_motor.h.

◆ param_interface_name_

std::string TmcCoeMotor::param_interface_name_
protected

Definition at line 89 of file tmc_coe_motor.h.

◆ param_pub_actual_pos_

bool TmcCoeMotor::param_pub_actual_pos_
protected

Definition at line 78 of file tmc_coe_motor.h.

◆ param_pub_actual_trq_

bool TmcCoeMotor::param_pub_actual_trq_
protected

Definition at line 79 of file tmc_coe_motor.h.

◆ param_pub_actual_vel_

bool TmcCoeMotor::param_pub_actual_vel_
protected

Definition at line 77 of file tmc_coe_motor.h.

◆ param_pub_rate_tmc_coe_info_

float TmcCoeMotor::param_pub_rate_tmc_coe_info_
protected

Definition at line 90 of file tmc_coe_motor.h.

◆ param_SDO_PDO_retries_

int TmcCoeMotor::param_SDO_PDO_retries_
protected

Definition at line 75 of file tmc_coe_motor.h.

◆ param_tmc_cmd_abspos_topic_

std::string TmcCoeMotor::param_tmc_cmd_abspos_topic_
protected

Definition at line 82 of file tmc_coe_motor.h.

◆ param_tmc_cmd_relpos_topic_

std::string TmcCoeMotor::param_tmc_cmd_relpos_topic_
protected

Definition at line 83 of file tmc_coe_motor.h.

◆ param_tmc_cmd_trq_topic_

std::string TmcCoeMotor::param_tmc_cmd_trq_topic_
protected

Definition at line 84 of file tmc_coe_motor.h.

◆ param_tmc_cmd_vel_topic_

std::string TmcCoeMotor::param_tmc_cmd_vel_topic_
protected

Definition at line 81 of file tmc_coe_motor.h.

◆ param_tmc_coe_info_topic_

std::string TmcCoeMotor::param_tmc_coe_info_topic_
protected

Definition at line 80 of file tmc_coe_motor.h.

◆ param_wheel_diameter_

float TmcCoeMotor::param_wheel_diameter_
protected

Definition at line 85 of file tmc_coe_motor.h.

◆ s_namespace_

std::string TmcCoeMotor::s_namespace_
protected

Definition at line 72 of file tmc_coe_motor.h.

◆ s_node_name_

std::string TmcCoeMotor::s_node_name_
protected

Definition at line 71 of file tmc_coe_motor.h.

◆ seq_ctr_

uint32_t TmcCoeMotor::seq_ctr_
protected

Definition at line 60 of file tmc_coe_motor.h.

◆ slave_number_

uint8_t TmcCoeMotor::slave_number_
protected

Definition at line 74 of file tmc_coe_motor.h.

◆ timer_callback_

ros::Timer TmcCoeMotor::timer_callback_
protected

Definition at line 56 of file tmc_coe_motor.h.

◆ tmc_cmd_abspos_sub_

ros::Subscriber TmcCoeMotor::tmc_cmd_abspos_sub_
protected

Definition at line 68 of file tmc_coe_motor.h.

◆ tmc_cmd_relpos_sub_

ros::Subscriber TmcCoeMotor::tmc_cmd_relpos_sub_
protected

Definition at line 69 of file tmc_coe_motor.h.

◆ tmc_cmd_vel_sub_

ros::Subscriber TmcCoeMotor::tmc_cmd_vel_sub_
protected

Definition at line 67 of file tmc_coe_motor.h.

◆ tmc_coe_info_msg_

adi_tmc_coe::TmcCoeInfo TmcCoeMotor::tmc_coe_info_msg_
protected

Definition at line 58 of file tmc_coe_motor.h.

◆ tmc_coe_info_pub_

ros::Publisher TmcCoeMotor::tmc_coe_info_pub_
protected

Definition at line 57 of file tmc_coe_motor.h.


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


adi_tmc_coe
Author(s):
autogenerated on Sun Feb 2 2025 03:07:24