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

#include <tmcl_stepper_motor.h>

Inheritance diagram for StepperMotor:
Inheritance graph
[legend]

Public Member Functions

void init () override
 
 StepperMotor (ros::NodeHandle *p_nh, TmclInterpreter *p_tmcl_interpreter, uint16_t module_number, uint8_t motor_number)
 
 ~StepperMotor () override
 
- Public Member Functions inherited from Motor
 Motor (ros::NodeHandle *p_nh, TmclInterpreter *p_tmcl_interpreter, uint16_t module_number, uint8_t motor_number)
 
virtual ~Motor ()
 

Private Member Functions

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

Private Attributes

stepper_comm_mode_t comm_mode_
 
uint16_t microstep_resolution_
 
uint32_t motor_fullstep_resolution_
 

Additional Inherited Members

- Protected Member Functions inherited from Motor
void initPublisher ()
 
- Protected Attributes inherited from Motor
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_
 

Detailed Description

Definition at line 19 of file tmcl_stepper_motor.h.

Constructor & Destructor Documentation

◆ StepperMotor()

StepperMotor::StepperMotor ( 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_stepper_motor.cpp.

◆ ~StepperMotor()

StepperMotor::~StepperMotor ( )
override

Definition at line 19 of file tmcl_stepper_motor.cpp.

Member Function Documentation

◆ cmdAbsPosCallback()

void StepperMotor::cmdAbsPosCallback ( const std_msgs::Int32  msg)
overrideprivatevirtual

Reimplemented from Motor.

Definition at line 301 of file tmcl_stepper_motor.cpp.

◆ cmdRelPosCallback()

void StepperMotor::cmdRelPosCallback ( const std_msgs::Int32  msg)
overrideprivatevirtual

Reimplemented from Motor.

Definition at line 333 of file tmcl_stepper_motor.cpp.

◆ cmdTrqCallback()

void StepperMotor::cmdTrqCallback ( const std_msgs::Int32  msg)
overrideprivatevirtual

Reimplemented from Motor.

Definition at line 365 of file tmcl_stepper_motor.cpp.

◆ cmdVelCallback()

void StepperMotor::cmdVelCallback ( const geometry_msgs::Twist &  msg)
overrideprivatevirtual

Reimplemented from Motor.

Definition at line 257 of file tmcl_stepper_motor.cpp.

◆ init()

void StepperMotor::init ( )
overridevirtual

Reimplemented from Motor.

Definition at line 24 of file tmcl_stepper_motor.cpp.

◆ initSubscriber()

void StepperMotor::initSubscriber ( )
overrideprivatevirtual

Reimplemented from Motor.

Definition at line 235 of file tmcl_stepper_motor.cpp.

◆ rosPublishTmcInfo()

void StepperMotor::rosPublishTmcInfo ( const ros::TimerEvent event)
overrideprivatevirtual

Reimplemented from Motor.

Definition at line 127 of file tmcl_stepper_motor.cpp.

Member Data Documentation

◆ comm_mode_

stepper_comm_mode_t StepperMotor::comm_mode_
private

Definition at line 46 of file tmcl_stepper_motor.h.

◆ microstep_resolution_

uint16_t StepperMotor::microstep_resolution_
private

Definition at line 43 of file tmcl_stepper_motor.h.

◆ motor_fullstep_resolution_

uint32_t StepperMotor::motor_fullstep_resolution_
private

Definition at line 44 of file tmcl_stepper_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