#include <tmcl_motor.h>
Definition at line 26 of file tmcl_motor.h.
◆ Motor()
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()
◆ cmdAbsPosCallback()
void Motor::cmdAbsPosCallback |
( |
const std_msgs::Int32 |
msg | ) |
|
|
protectedvirtual |
◆ cmdRelPosCallback()
void Motor::cmdRelPosCallback |
( |
const std_msgs::Int32 |
msg | ) |
|
|
protectedvirtual |
◆ cmdTrqCallback()
void Motor::cmdTrqCallback |
( |
const std_msgs::Int32 |
msg | ) |
|
|
protectedvirtual |
◆ cmdVelCallback()
void Motor::cmdVelCallback |
( |
const geometry_msgs::Twist & |
msg | ) |
|
|
protectedvirtual |
◆ init()
◆ initParams()
void Motor::initParams |
( |
| ) |
|
|
private |
◆ initPublisher()
void Motor::initPublisher |
( |
| ) |
|
|
protected |
◆ initSubscriber()
void Motor::initSubscriber |
( |
| ) |
|
|
protectedvirtual |
◆ rosPublishTmcInfo()
◆ frame_id_
std::string Motor::frame_id_ |
|
protected |
◆ module_number_
uint16_t Motor::module_number_ |
|
protected |
◆ motor_number_
uint8_t Motor::motor_number_ |
|
protected |
◆ p_nh_
◆ p_tmcl_interpreter_
◆ param_add_ratio_pos_
float Motor::param_add_ratio_pos_ |
|
protected |
◆ param_add_ratio_trq_
float Motor::param_add_ratio_trq_ |
|
protected |
◆ param_add_ratio_vel_
float Motor::param_add_ratio_vel_ |
|
protected |
◆ param_comm_interface_name_
std::string Motor::param_comm_interface_name_ |
|
protected |
◆ param_en_pub_tmc_info_
bool Motor::param_en_pub_tmc_info_ |
|
protected |
◆ param_pub_actual_pos_
bool Motor::param_pub_actual_pos_ |
|
protected |
◆ param_pub_actual_trq_
bool Motor::param_pub_actual_trq_ |
|
protected |
◆ param_pub_actual_vel_
bool Motor::param_pub_actual_vel_ |
|
protected |
◆ param_pub_rate_tmc_info_
float Motor::param_pub_rate_tmc_info_ |
|
protected |
◆ param_tmc_cmd_abspos_topic_
std::string Motor::param_tmc_cmd_abspos_topic_ |
|
protected |
◆ param_tmc_cmd_relpos_topic_
std::string Motor::param_tmc_cmd_relpos_topic_ |
|
protected |
◆ param_tmc_cmd_trq_topic_
std::string Motor::param_tmc_cmd_trq_topic_ |
|
protected |
◆ param_tmc_cmd_vel_topic_
std::string Motor::param_tmc_cmd_vel_topic_ |
|
protected |
◆ param_tmc_info_topic_
std::string Motor::param_tmc_info_topic_ |
|
protected |
◆ param_wheel_diameter_
float Motor::param_wheel_diameter_ |
|
protected |
◆ s_namespace_
std::string Motor::s_namespace_ |
|
protected |
◆ s_node_name_
std::string Motor::s_node_name_ |
|
protected |
◆ seq_ctr_
◆ timer_callback_
◆ tmc_cmd_abspos_sub_
◆ tmc_cmd_relpos_sub_
◆ tmc_cmd_trq_sub_
◆ tmc_cmd_vel_sub_
◆ tmc_info_msg_
adi_tmcl::TmcInfo Motor::tmc_info_msg_ |
|
protected |
◆ tmc_info_pub_
The documentation for this class was generated from the following files: