include
adi_tmc_coe
tmc_coe_bldc_motor.h
Go to the documentation of this file.
1
6
#ifndef TMC_COE_BLDC_MOTOR_H
7
#define TMC_COE_BLDC_MOTOR_H
8
9
#include "
tmc_coe_motor.h
"
10
11
/* Commutation Modes available for BLDC Motors */
12
typedef
enum
13
{
14
BLDC_DISABLED_MOTOR
= 0,
15
BLDC_OPENLOOP_MOTOR
,
16
BLDC_CLOSEDLOOP_MOTOR
17
}
bldc_comm_mode_t
;
18
19
class
TmcCoeBLDCMotor
:
public
TmcCoeMotor
20
{
21
private
:
22
23
/* Publisher */
24
void
rosPublishTmcCoeInfo
(
const
ros::TimerEvent
& event)
override
;
25
26
/* Subscriber */
27
void
initSubscriber
()
override
;
28
void
cmdVelCallback
(
const
geometry_msgs::Twist& msg)
override
;
29
void
cmdAbsPosCallback
(
const
std_msgs::Int32 msg)
override
;
30
void
cmdRelPosCallback
(
const
std_msgs::Int32 msg)
override
;
31
32
uint32_t
encoder_steps_
;
33
int32_t
position_scaler_
;
34
bldc_comm_mode_t
commutation_mode_
;
35
36
public
:
37
TmcCoeBLDCMotor
(
ros::NodeHandle
*p_nh,
TmcCoeInterpreter
* p_tmc_coe_interpreter,
38
uint8_t
slave_number,
uint8_t
motor_number);
39
~TmcCoeBLDCMotor
();
40
void
init
()
override
;
41
};
42
43
#endif
/* TMC_COE_BLDC_MOTOR_H */
uint8_t
unsigned char uint8_t
TmcCoeBLDCMotor::cmdAbsPosCallback
void cmdAbsPosCallback(const std_msgs::Int32 msg) override
Definition:
tmc_coe_bldc_motor.cpp:259
TmcCoeBLDCMotor::initSubscriber
void initSubscriber() override
Definition:
tmc_coe_bldc_motor.cpp:182
TmcCoeBLDCMotor::TmcCoeBLDCMotor
TmcCoeBLDCMotor(ros::NodeHandle *p_nh, TmcCoeInterpreter *p_tmc_coe_interpreter, uint8_t slave_number, uint8_t motor_number)
Definition:
tmc_coe_bldc_motor.cpp:11
tmc_coe_motor.h
BLDC_DISABLED_MOTOR
@ BLDC_DISABLED_MOTOR
Definition:
tmc_coe_bldc_motor.h:14
BLDC_CLOSEDLOOP_MOTOR
@ BLDC_CLOSEDLOOP_MOTOR
Definition:
tmc_coe_bldc_motor.h:16
TmcCoeBLDCMotor::cmdRelPosCallback
void cmdRelPosCallback(const std_msgs::Int32 msg) override
Definition:
tmc_coe_bldc_motor.cpp:329
BLDC_OPENLOOP_MOTOR
@ BLDC_OPENLOOP_MOTOR
Definition:
tmc_coe_bldc_motor.h:15
uint32_t
unsigned int uint32_t
TmcCoeBLDCMotor::position_scaler_
int32_t position_scaler_
Definition:
tmc_coe_bldc_motor.h:33
TmcCoeBLDCMotor::~TmcCoeBLDCMotor
~TmcCoeBLDCMotor()
Definition:
tmc_coe_bldc_motor.cpp:19
TmcCoeBLDCMotor::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist &msg) override
Definition:
tmc_coe_bldc_motor.cpp:205
ros::TimerEvent
TmcCoeBLDCMotor
Definition:
tmc_coe_bldc_motor.h:19
TmcCoeMotor
Definition:
tmc_coe_motor.h:47
int32_t
signed int int32_t
TmcCoeInterpreter
Definition:
tmc_coe_interpreter.h:148
TmcCoeBLDCMotor::init
void init() override
Definition:
tmc_coe_bldc_motor.cpp:26
bldc_comm_mode_t
bldc_comm_mode_t
Definition:
tmc_coe_bldc_motor.h:12
TmcCoeBLDCMotor::rosPublishTmcCoeInfo
void rosPublishTmcCoeInfo(const ros::TimerEvent &event) override
Definition:
tmc_coe_bldc_motor.cpp:102
TmcCoeBLDCMotor::encoder_steps_
uint32_t encoder_steps_
Definition:
tmc_coe_bldc_motor.h:32
ros::NodeHandle
TmcCoeBLDCMotor::commutation_mode_
bldc_comm_mode_t commutation_mode_
Definition:
tmc_coe_bldc_motor.h:34
adi_tmc_coe
Author(s):
autogenerated on Sun Feb 2 2025 03:07:24