include
tmcl_ros
tmcl_stepper_motor.h
Go to the documentation of this file.
1
6
#ifndef TMCL_STEPPER_MOTOR_H
7
#define TMCL_STEPPER_MOTOR_H
8
9
#include "
tmcl_motor.h
"
10
11
/* List Commutation Modes availaable for BLDC motors */
12
typedef
enum
13
{
14
STEPPER_OPENLOOP_MOTOR
= 0,
15
STEPPER_CLOSEDLOOP_MOTOR
,
16
STEPPER_COMM_MODE_MAX
/* This should not be used */
17
}
stepper_comm_mode_t
;
18
19
class
StepperMotor
:
public
Motor
20
{
21
public
:
22
/* Constructor */
23
StepperMotor
(
ros::NodeHandle
* p_nh,
TmclInterpreter
*p_tmcl_interpreter,
24
uint16_t module_number, uint8_t motor_number);
25
26
/* Destructor */
27
~StepperMotor
()
override
;
28
29
/* Initialize Stepper Motor */
30
void
init
()
override
;
31
32
private
:
33
/* Publisher */
34
void
rosPublishTmcInfo
(
const
ros::TimerEvent
& event)
override
;
35
36
/* Subscriber */
37
void
initSubscriber
()
override
;
38
void
cmdVelCallback
(
const
geometry_msgs::Twist& msg)
override
;
39
void
cmdAbsPosCallback
(
const
std_msgs::Int32 msg)
override
;
40
void
cmdRelPosCallback
(
const
std_msgs::Int32 msg)
override
;
41
void
cmdTrqCallback
(
const
std_msgs::Int32 msg)
override
;
42
43
uint16_t
microstep_resolution_
;
44
uint32_t
motor_fullstep_resolution_
;
45
46
stepper_comm_mode_t
comm_mode_
;
47
};
48
49
#endif // TMCL_STEPPER_MOTOR_H
tmcl_motor.h
STEPPER_COMM_MODE_MAX
@ STEPPER_COMM_MODE_MAX
Definition:
tmcl_stepper_motor.h:16
StepperMotor::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist &msg) override
Definition:
tmcl_stepper_motor.cpp:257
StepperMotor::microstep_resolution_
uint16_t microstep_resolution_
Definition:
tmcl_stepper_motor.h:43
StepperMotor::init
void init() override
Definition:
tmcl_stepper_motor.cpp:24
StepperMotor::rosPublishTmcInfo
void rosPublishTmcInfo(const ros::TimerEvent &event) override
Definition:
tmcl_stepper_motor.cpp:127
StepperMotor::motor_fullstep_resolution_
uint32_t motor_fullstep_resolution_
Definition:
tmcl_stepper_motor.h:44
StepperMotor::StepperMotor
StepperMotor(ros::NodeHandle *p_nh, TmclInterpreter *p_tmcl_interpreter, uint16_t module_number, uint8_t motor_number)
Definition:
tmcl_stepper_motor.cpp:11
StepperMotor::cmdTrqCallback
void cmdTrqCallback(const std_msgs::Int32 msg) override
Definition:
tmcl_stepper_motor.cpp:365
StepperMotor::cmdRelPosCallback
void cmdRelPosCallback(const std_msgs::Int32 msg) override
Definition:
tmcl_stepper_motor.cpp:333
StepperMotor::initSubscriber
void initSubscriber() override
Definition:
tmcl_stepper_motor.cpp:235
StepperMotor::cmdAbsPosCallback
void cmdAbsPosCallback(const std_msgs::Int32 msg) override
Definition:
tmcl_stepper_motor.cpp:301
STEPPER_OPENLOOP_MOTOR
@ STEPPER_OPENLOOP_MOTOR
Definition:
tmcl_stepper_motor.h:14
stepper_comm_mode_t
stepper_comm_mode_t
Definition:
tmcl_stepper_motor.h:12
STEPPER_CLOSEDLOOP_MOTOR
@ STEPPER_CLOSEDLOOP_MOTOR
Definition:
tmcl_stepper_motor.h:15
StepperMotor::comm_mode_
stepper_comm_mode_t comm_mode_
Definition:
tmcl_stepper_motor.h:46
TmclInterpreter
Definition:
tmcl_interpreter.h:98
ros::TimerEvent
StepperMotor
Definition:
tmcl_stepper_motor.h:19
Motor
Definition:
tmcl_motor.h:26
StepperMotor::~StepperMotor
~StepperMotor() override
Definition:
tmcl_stepper_motor.cpp:19
ros::NodeHandle
adi_tmcl
Author(s):
autogenerated on Wed Apr 2 2025 02:43:01