Class Motor
Defined in File tmcl_motor.hpp
Inheritance Relationships
Derived Types
public BldcMotor
(Class BldcMotor)public StepperMotor
(Class StepperMotor)
Class Documentation
-
class Motor
Copyright (c) 2023-2024 Analog Devices, Inc. All Rights Reserved. This software is proprietary to Analog Devices, Inc. and its licensors.
Subclassed by BldcMotor, StepperMotor
Public Functions
-
virtual ~Motor()
-
uint8_t getMotorNumber()
-
std::string getMotorName()
-
virtual void init()
Protected Attributes
-
rclcpp::Node::SharedPtr p_node_
-
TmclInterpreter *p_tmcl_interpreter_
-
rclcpp::Publisher<adi_tmcl::msg::TmcInfo>::SharedPtr publisher_
-
rclcpp::TimerBase::SharedPtr publisher_timer_
-
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr subscription_cmd_vel_
-
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr subscription_cmd_abspos_
-
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr subscription_cmd_relpos_
-
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr subscription_cmd_trq_
-
bool param_en_pub_tmc_info_
-
std::string param_tmc_info_topic_
-
uint8_t param_pub_rate_tmc_info_
-
bool param_pub_actual_vel_
-
bool param_pub_actual_pos_
-
bool param_pub_actual_trq_
-
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_additional_ratio_vel_
-
double param_additional_ratio_pos_
-
double param_additional_ratio_trq_
-
std::string param_comm_interface_name_
-
uint32_t module_number_
-
std::string tmc_info_frame_id_
-
virtual ~Motor()