Class TmcCoeMotor
Defined in File tmc_coe_motor.hpp
Inheritance Relationships
Derived Types
public TmcCoeBldcMotor
(Class TmcCoeBldcMotor)public TmcCoeStepperMotor
(Class TmcCoeStepperMotor)
Class Documentation
-
class TmcCoeMotor
Subclassed by TmcCoeBldcMotor, TmcCoeStepperMotor
Protected Functions
-
void initPublisher()
-
virtual void initSubscriber()
-
virtual void publishTmcCoeInfo()
Protected Attributes
-
rclcpp::Node::SharedPtr p_node_
-
TmcCoeInterpreter *p_tmc_coe_interpreter_
-
uint8_t slave_number_
-
uint8_t motor_number_
-
std::string device_name_
-
rclcpp::Publisher<adi_tmc_coe_interfaces::msg::TmcCoeInfo>::SharedPtr tmc_coe_info_pub_
-
rclcpp::TimerBase::SharedPtr tmc_coe_info_pub_timer_
-
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_
-
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr cmd_abspos_sub_
-
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr cmd_relpos_sub_
-
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr cmd_trq_sub_
-
bool param_en_pub_tmc_info_
-
bool param_pub_actual_vel_
-
bool param_pub_actual_pos_
-
bool param_pub_actual_trq_
-
std::string param_tmc_info_topic_
-
std::string param_tmc_cmd_vel_topic_
-
std::string param_tmc_cmd_abspos_topic_
-
std::string param_tmc_cmd_relpos_topic_
-
std::string param_tmc_cmd_trq_topic_
-
double param_wheel_diameter_
-
double param_add_ratio_vel_
-
double param_add_ratio_pos_
-
double param_add_ratio_trq_
-
std::string tmc_coe_info_frame_id_
-
int param_pub_rate_tmc_coe_info_
-
void initPublisher()