Template Class NodeCanopen402Driver

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public ros2_canopen::node_interfaces::NodeCanopenProxyDriver< NODETYPE >

Class Documentation

template<class NODETYPE>
class NodeCanopen402Driver : public ros2_canopen::node_interfaces::NodeCanopenProxyDriver<NODETYPE>

Public Functions

NodeCanopen402Driver(NODETYPE *node)
virtual void init(bool called_from_base) override
virtual void configure(bool called_from_base) override
virtual void activate(bool called_from_base) override
virtual void deactivate(bool called_from_base) override
virtual void add_to_master() override
inline virtual double get_effort(uint8_t channel = 0)
inline virtual double get_speed(uint8_t channel = 0)
inline virtual double get_position(uint8_t channel = 0)
inline virtual uint16_t get_mode(uint8_t channel = 0)
void handle_init(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to initialise device.

Calls Motor402::handleInit function. Brings motor to enabled state and homes it.

Parameters:
  • request[in]

  • response[out]

void handle_enable(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to enable device.

Calls Motor402::handleEnable function. Brings motor to enabled state.

Parameters:
  • request[in]

  • response[out]

void handle_disable(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to disable device.

Calls Motor402::handleDisable function. Brings motor to switched on disabled state.

Parameters:
  • request[in]

  • response[out]

bool init_motor(uint8_t channel = 0)

Method to initialise device.

Calls Motor402::handleInit function. Brings motor to enabled state and homes it.

Parameters:

void

Returns:

bool Indicates initialisation procedure result

void handle_recover(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to recover device.

Calls Motor402::handleRecover function. Resets faults and brings motor to enabled state.

Parameters:
  • request[in]

  • response[out]

bool recover_motor(uint8_t channel = 0)

Method to recover device.

Calls Motor402::handleRecover function. Resets faults and brings motor to enabled state.

Parameters:

void

Returns:

bool

void handle_halt(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to halt device.

Calls Motor402::handleHalt function. Calls Quickstop. Resulting Motor state depends on devices configuration specifically object 0x605A.

Parameters:
  • request[in]

  • response[out]

bool halt_motor(uint8_t channel = 0)

Method to halt device.

Calls Motor402::handleHalt function. Calls Quickstop. Resulting Motor state depends on devices configuration specifically object 0x605A.

Parameters:

void

Returns:

bool

bool set_operation_mode(uint16_t mode, uint8_t channel = 0)

Service Callback to set operation mode.

Calls Motor402::enterModeAndWait with requested Operation Mode.

Parameters:
  • request[in] Requested Operation Mode as MotorBase::Profiled_Position or MotorBase::Profiled_Velocity or MotorBase::Profiled_Torque or MotorBase::Cyclic_Position or MotorBase::Cyclic_Velocity or MotorBase::Cyclic_Torque or MotorBase::Interpolated_Position

  • response[out]

void handle_set_mode_position(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to set profiled position mode.

Calls Motor402::enterModeAndWait with Profiled Position Mode as Target Operation Mode. If successful, the motor was transitioned to Profiled Position Mode.

Parameters:
  • request[in]

  • response[out]

void handle_set_mode_velocity(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to set profiled velocity mode.

Calls Motor402::enterModeAndWait with Profiled Velocity Mode as Target Operation Mode. If successful, the motor was transitioned to Profiled Velocity Mode.

Parameters:
  • request[in]

  • response[out]

void handle_set_mode_cyclic_position(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to set cyclic position mode.

Calls Motor402::enterModeAndWait with Cyclic Position Mode as Target Operation Mode. If successful, the motor was transitioned to Cyclic Position Mode.

Parameters:
  • request[in]

  • response[out]

void handle_set_mode_interpolated_position(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to set interpolated position mode.

Calls Motor402::enterModeAndWait with Interpolated Position Mode as Target Operation Mode. If successful, the motor was transitioned to Interpolated Position Mode. This only supports linear mode.

Parameters:
  • request[in]

  • response[out]

void handle_set_mode_cyclic_velocity(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to set cyclic velocity mode.

Calls Motor402::enterModeAndWait with Cyclic Velocity Mode as Target Operation Mode. If successful, the motor was transitioned to Cyclic Velocity Mode.

Parameters:
  • request[in]

  • response[out]

void handle_set_mode_torque(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to set profiled torque mode.

Calls Motor402::enterModeAndWait with Profiled Torque Mode as Target Operation Mode. If successful, the motor was transitioned to Profiled Torque Mode.

Parameters:
  • request[in]

  • response[out]

void handle_set_mode_cyclic_torque(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0)

Service Callback to set cyclic torque mode.

Calls Motor402::enterModeAndWait with Cyclic Torque Mode as Target Operation Mode. If successful, the motor was transitioned to Cyclic Torque Mode.

Parameters:
  • request[in]

  • response[out]

void handle_set_target(const canopen_interfaces::srv::COTargetDouble::Request::SharedPtr request, canopen_interfaces::srv::COTargetDouble::Response::SharedPtr response, const uint8_t channel = 0)

Service Callback to set target.

Calls Motor402::setTarget and sets the requested target value. Note that the resulting movement is dependent on the Operation Mode and the drives state.

Parameters:
  • request[in]

  • response[out]

bool set_target(double target, uint8_t channel = 0)

Method to set target.

Calls Motor402::setTarget and sets the requested target value. Note that the resulting movement is dependent on the Operation Mode and the drives state.

Parameters:
  • double[in] target value

  • uint8_t[in] channel (default 0 for backward compatibility)

Returns:

bool

Protected Functions

void publish()
virtual void poll_timer_callback() override
void diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper &stat) override
void configure_common()
void create_per_channel_services()

Protected Attributes

std::vector<ChannelContext> channels_
uint8_t num_channels_
std::vector<std::string> channel_names_
rclcpp::TimerBase::SharedPtr timer_
rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr publish_joint_state
double scale_pos_to_dev_
double scale_pos_from_dev_
double scale_vel_to_dev_
double scale_vel_from_dev_
double scale_eff_from_dev_
double offset_pos_to_dev_
double offset_pos_from_dev_
ros2_canopen::State402::InternalState switching_state_
int homing_timeout_seconds_
struct ChannelContext

Public Members

std::shared_ptr<Motor402> motor
double scale_pos_to_dev = {1000.0}
double scale_pos_from_dev = {0.001}
double scale_vel_to_dev = {1000.0}
double scale_vel_from_dev = {0.001}
double scale_eff_from_dev = {0.001}
double offset_pos_to_dev = {0.0}
double offset_pos_from_dev = {0.0}
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_init
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_enable
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_disable
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_halt
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_recover
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_position
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_torque
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_velocity
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_velocity
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_position
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_torque
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_interpolated_position
rclcpp::Service<canopen_interfaces::srv::COTargetDouble>::SharedPtr handle_set_target