Template Class NodeCanopen402Driver

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_speed()
inline virtual double get_position()
inline virtual uint16_t get_mode()
void handle_init(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)

Service Callback to initialise device.

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

Parameters:
  • request[in]

  • response[out]

bool init_motor()

Method to initialise device.

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

Parameters:

void[in]

Returns:

bool Indicates initialisation procedure result

void handle_recover(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)

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()

Method to recover device.

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

Parameters:

void[in]

Returns:

bool

void handle_halt(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)

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()

Method to halt device.

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

Parameters:

void[in]

Returns:

bool

void handle_set_mode_position(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)

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]

bool set_operation_mode(uint16_t mode)
bool set_mode_position()

Method 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:

void[in]

Returns:

bool

void handle_set_mode_velocity(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)

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]

bool set_mode_velocity()

Method 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:

void[in]

Returns:

bool

void handle_set_mode_cyclic_position(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)

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)

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]

bool set_mode_interpolated_position()

Method 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:
  • void[in]

  • bool[out]

bool set_mode_cyclic_position()

Method 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:

void[in]

Returns:

bool

void handle_set_mode_cyclic_velocity(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)

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]

bool set_mode_cyclic_velocity()

Method 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:

void[in]

Returns:

bool

void handle_set_mode_torque(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)

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]

bool set_mode_torque()

Method 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:

void[in]

Returns:

bool

void handle_set_target(const canopen_interfaces::srv::COTargetDouble::Request::SharedPtr request, canopen_interfaces::srv::COTargetDouble::Response::SharedPtr response)

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)

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

Returns:

bool

Protected Functions

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

Protected Attributes

std::shared_ptr<Motor402> motor_
rclcpp::TimerBase::SharedPtr timer_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_init_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_halt_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_recover_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_position_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_torque_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_velocity_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_velocity_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_position_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_interpolated_position_service
rclcpp::Service<canopen_interfaces::srv::COTargetDouble>::SharedPtr handle_set_target_service
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_
ros2_canopen::State402::InternalState switching_state_