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

#include <tmcl_motor.h>

Inheritance diagram for Motor:
Inheritance graph
[legend]

Public Member Functions

virtual void init ()
 
 Motor (ros::NodeHandle *p_nh, TmclInterpreter *p_tmcl_interpreter, uint16_t module_number, uint8_t motor_number)
 
virtual ~Motor ()
 

Protected Member Functions

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

Protected Attributes

std::string frame_id_
 
uint16_t module_number_
 
uint8_t motor_number_
 
ros::NodeHandlep_nh_
 
TmclInterpreterp_tmcl_interpreter_
 
float param_add_ratio_pos_
 
float param_add_ratio_trq_
 
float param_add_ratio_vel_
 
std::string param_comm_interface_name_
 
bool param_en_pub_tmc_info_
 
bool param_pub_actual_pos_
 
bool param_pub_actual_trq_
 
bool param_pub_actual_vel_
 
float param_pub_rate_tmc_info_
 
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_info_topic_
 
float param_wheel_diameter_
 
std::string s_namespace_
 
std::string s_node_name_
 
uint32_t seq_ctr_
 
ros::Timer timer_callback_
 
ros::Subscriber tmc_cmd_abspos_sub_
 
ros::Subscriber tmc_cmd_relpos_sub_
 
ros::Subscriber tmc_cmd_trq_sub_
 
ros::Subscriber tmc_cmd_vel_sub_
 
adi_tmcl::TmcInfo tmc_info_msg_
 
ros::Publisher tmc_info_pub_
 

Private Member Functions

void initParams ()
 

Detailed Description

Definition at line 26 of file tmcl_motor.h.

Constructor & Destructor Documentation

◆ Motor()

Motor::Motor ( ros::NodeHandle p_nh,
TmclInterpreter p_tmcl_interpreter,
uint16_t  module_number,
uint8_t  motor_number 
)

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

Definition at line 11 of file tmcl_motor.cpp.

◆ ~Motor()

Motor::~Motor ( )
virtual

Definition at line 23 of file tmcl_motor.cpp.

Member Function Documentation

◆ cmdAbsPosCallback()

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

Reimplemented in BLDCMotor, and StepperMotor.

Definition at line 326 of file tmcl_motor.cpp.

◆ cmdRelPosCallback()

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

Reimplemented in BLDCMotor, and StepperMotor.

Definition at line 344 of file tmcl_motor.cpp.

◆ cmdTrqCallback()

void Motor::cmdTrqCallback ( const std_msgs::Int32  msg)
protectedvirtual

Reimplemented in StepperMotor.

Definition at line 362 of file tmcl_motor.cpp.

◆ cmdVelCallback()

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

Reimplemented in BLDCMotor, and StepperMotor.

Definition at line 292 of file tmcl_motor.cpp.

◆ init()

void Motor::init ( )
virtual

Reimplemented in BLDCMotor, and StepperMotor.

Definition at line 30 of file tmcl_motor.cpp.

◆ initParams()

void Motor::initParams ( )
private

Definition at line 40 of file tmcl_motor.cpp.

◆ initPublisher()

void Motor::initPublisher ( )
protected

Definition at line 167 of file tmcl_motor.cpp.

◆ initSubscriber()

void Motor::initSubscriber ( )
protectedvirtual

Reimplemented in BLDCMotor, and StepperMotor.

Definition at line 281 of file tmcl_motor.cpp.

◆ rosPublishTmcInfo()

void Motor::rosPublishTmcInfo ( const ros::TimerEvent event)
protectedvirtual

Reimplemented in BLDCMotor, and StepperMotor.

Definition at line 204 of file tmcl_motor.cpp.

Member Data Documentation

◆ frame_id_

std::string Motor::frame_id_
protected

Definition at line 70 of file tmcl_motor.h.

◆ module_number_

uint16_t Motor::module_number_
protected

Definition at line 71 of file tmcl_motor.h.

◆ motor_number_

uint8_t Motor::motor_number_
protected

Definition at line 72 of file tmcl_motor.h.

◆ p_nh_

ros::NodeHandle* Motor::p_nh_
protected

Definition at line 63 of file tmcl_motor.h.

◆ p_tmcl_interpreter_

TmclInterpreter* Motor::p_tmcl_interpreter_
protected

Definition at line 64 of file tmcl_motor.h.

◆ param_add_ratio_pos_

float Motor::param_add_ratio_pos_
protected

Definition at line 84 of file tmcl_motor.h.

◆ param_add_ratio_trq_

float Motor::param_add_ratio_trq_
protected

Definition at line 85 of file tmcl_motor.h.

◆ param_add_ratio_vel_

float Motor::param_add_ratio_vel_
protected

Definition at line 83 of file tmcl_motor.h.

◆ param_comm_interface_name_

std::string Motor::param_comm_interface_name_
protected

Definition at line 67 of file tmcl_motor.h.

◆ param_en_pub_tmc_info_

bool Motor::param_en_pub_tmc_info_
protected

Definition at line 48 of file tmcl_motor.h.

◆ param_pub_actual_pos_

bool Motor::param_pub_actual_pos_
protected

Definition at line 80 of file tmcl_motor.h.

◆ param_pub_actual_trq_

bool Motor::param_pub_actual_trq_
protected

Definition at line 81 of file tmcl_motor.h.

◆ param_pub_actual_vel_

bool Motor::param_pub_actual_vel_
protected

Definition at line 79 of file tmcl_motor.h.

◆ param_pub_rate_tmc_info_

float Motor::param_pub_rate_tmc_info_
protected

Definition at line 46 of file tmcl_motor.h.

◆ param_tmc_cmd_abspos_topic_

std::string Motor::param_tmc_cmd_abspos_topic_
protected

Definition at line 76 of file tmcl_motor.h.

◆ param_tmc_cmd_relpos_topic_

std::string Motor::param_tmc_cmd_relpos_topic_
protected

Definition at line 77 of file tmcl_motor.h.

◆ param_tmc_cmd_trq_topic_

std::string Motor::param_tmc_cmd_trq_topic_
protected

Definition at line 78 of file tmcl_motor.h.

◆ param_tmc_cmd_vel_topic_

std::string Motor::param_tmc_cmd_vel_topic_
protected

Definition at line 75 of file tmcl_motor.h.

◆ param_tmc_info_topic_

std::string Motor::param_tmc_info_topic_
protected

Definition at line 47 of file tmcl_motor.h.

◆ param_wheel_diameter_

float Motor::param_wheel_diameter_
protected

Definition at line 82 of file tmcl_motor.h.

◆ s_namespace_

std::string Motor::s_namespace_
protected

Definition at line 69 of file tmcl_motor.h.

◆ s_node_name_

std::string Motor::s_node_name_
protected

Definition at line 68 of file tmcl_motor.h.

◆ seq_ctr_

uint32_t Motor::seq_ctr_
protected

Definition at line 49 of file tmcl_motor.h.

◆ timer_callback_

ros::Timer Motor::timer_callback_
protected

Definition at line 43 of file tmcl_motor.h.

◆ tmc_cmd_abspos_sub_

ros::Subscriber Motor::tmc_cmd_abspos_sub_
protected

Definition at line 58 of file tmcl_motor.h.

◆ tmc_cmd_relpos_sub_

ros::Subscriber Motor::tmc_cmd_relpos_sub_
protected

Definition at line 59 of file tmcl_motor.h.

◆ tmc_cmd_trq_sub_

ros::Subscriber Motor::tmc_cmd_trq_sub_
protected

Definition at line 60 of file tmcl_motor.h.

◆ tmc_cmd_vel_sub_

ros::Subscriber Motor::tmc_cmd_vel_sub_
protected

Definition at line 57 of file tmcl_motor.h.

◆ tmc_info_msg_

adi_tmcl::TmcInfo Motor::tmc_info_msg_
protected

Definition at line 45 of file tmcl_motor.h.

◆ tmc_info_pub_

ros::Publisher Motor::tmc_info_pub_
protected

Definition at line 44 of file tmcl_motor.h.


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


adi_tmcl
Author(s):
autogenerated on Wed Apr 2 2025 02:43:01