Skip to content

Commit

Permalink
Merge pull request #314 from ipa-vsp/impl_set_operation_mode
Browse files Browse the repository at this point in the history
Remove multiple mode set functions.
  • Loading branch information
ipa-vsp authored Dec 12, 2024
2 parents eb219eb + 8671938 commit f1fef24
Show file tree
Hide file tree
Showing 5 changed files with 35 additions and 270 deletions.
17 changes: 0 additions & 17 deletions canopen_402_driver/include/canopen_402_driver/cia402_driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,23 +81,6 @@ class Cia402Driver : public ros2_canopen::CanopenDriver

bool halt_motor() { return node_canopen_402_driver_->halt_motor(); }

bool set_mode_position() { return node_canopen_402_driver_->set_mode_position(); }

bool set_mode_velocity() { return node_canopen_402_driver_->set_mode_velocity(); }

bool set_mode_cyclic_position() { return node_canopen_402_driver_->set_mode_cyclic_position(); }

bool set_mode_cyclic_velocity() { return node_canopen_402_driver_->set_mode_cyclic_velocity(); }

bool set_mode_torque() { return node_canopen_402_driver_->set_mode_torque(); }

bool set_mode_cyclic_torque() { return node_canopen_402_driver_->set_mode_cyclic_torque(); }

bool set_mode_interpolated_position()
{
return node_canopen_402_driver_->set_mode_interpolated_position();
}

uint16_t get_mode() { return node_canopen_402_driver_->get_mode(); }

bool set_operation_mode(uint16_t mode)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,21 +83,11 @@ class LifecycleCia402Driver : public ros2_canopen::LifecycleCanopenDriver

bool halt_motor() { return node_canopen_402_driver_->halt_motor(); }

bool set_mode_position() { return node_canopen_402_driver_->set_mode_position(); }
uint16_t get_mode() { return node_canopen_402_driver_->get_mode(); }

bool set_mode_velocity() { return node_canopen_402_driver_->set_mode_velocity(); }

bool set_mode_cyclic_position() { return node_canopen_402_driver_->set_mode_cyclic_position(); }

bool set_mode_cyclic_velocity() { return node_canopen_402_driver_->set_mode_cyclic_velocity(); }

bool set_mode_torque() { return node_canopen_402_driver_->set_mode_torque(); }

bool set_mode_cyclic_torque() { return node_canopen_402_driver_->set_mode_cyclic_torque(); }

bool set_mode_interpolated_position()
bool set_operation_mode(uint16_t mode)
{
return node_canopen_402_driver_->set_mode_interpolated_position();
return node_canopen_402_driver_->set_operation_mode(mode);
}
};
} // namespace ros2_canopen
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,33 +157,30 @@ class NodeCanopen402Driver : public NodeCanopenProxyDriver<NODETYPE>
bool halt_motor();

/**
* @brief Service Callback to set profiled position mode
* @brief Service Callback to set operation mode
*
* Calls Motor402::enterModeAndWait with Profiled Position Mode as
* Target Operation Mode. If successful, the motor was transitioned
* to Profiled Position Mode.
* Calls Motor402::enterModeAndWait with requested Operation Mode.
*
* @param [in] request
* @param [in] request 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
* @param [out] response
*/
void handle_set_mode_position(
const std_srvs::srv::Trigger::Request::SharedPtr request,
std_srvs::srv::Trigger::Response::SharedPtr response);

bool set_operation_mode(uint16_t mode);

/**
* @brief Method to set profiled position mode
* @brief 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.
*
* @param [in] void
*
* @return bool
* @param [in] request
* @param [out] response
*/
bool set_mode_position();
void handle_set_mode_position(
const std_srvs::srv::Trigger::Request::SharedPtr request,
std_srvs::srv::Trigger::Response::SharedPtr response);

/**
* @brief Service Callback to set profiled velocity mode
Expand All @@ -199,19 +196,6 @@ class NodeCanopen402Driver : public NodeCanopenProxyDriver<NODETYPE>
const std_srvs::srv::Trigger::Request::SharedPtr request,
std_srvs::srv::Trigger::Response::SharedPtr response);

/**
* @brief 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.
*
* @param [in] void
*
* @return bool
*/
bool set_mode_velocity();

/**
* @brief Service Callback to set cyclic position mode
*
Expand Down Expand Up @@ -240,31 +224,6 @@ class NodeCanopen402Driver : public NodeCanopenProxyDriver<NODETYPE>
const std_srvs::srv::Trigger::Request::SharedPtr request,
std_srvs::srv::Trigger::Response::SharedPtr response);

/**
* @brief 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.
*
* @param [in] void
* @param [out] bool
*/
bool set_mode_interpolated_position();

/**
* @brief 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.
*
* @param [in] void
*
* @return bool
*/
bool set_mode_cyclic_position();

/**
* @brief Service Callback to set cyclic velocity mode
*
Expand All @@ -279,19 +238,6 @@ class NodeCanopen402Driver : public NodeCanopenProxyDriver<NODETYPE>
const std_srvs::srv::Trigger::Request::SharedPtr request,
std_srvs::srv::Trigger::Response::SharedPtr response);

/**
* @brief 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.
*
* @param [in] void
*
* @return bool
*/
bool set_mode_cyclic_velocity();

/**
* @brief Service Callback to set profiled torque mode
*
Expand All @@ -306,19 +252,6 @@ class NodeCanopen402Driver : public NodeCanopenProxyDriver<NODETYPE>
const std_srvs::srv::Trigger::Request::SharedPtr request,
std_srvs::srv::Trigger::Response::SharedPtr response);

/**
* @brief 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.
*
* @param [in] void
*
* @return bool
*/
bool set_mode_torque();

/**
* @brief Service Callback to set cyclic torque mode
*
Expand All @@ -333,19 +266,6 @@ class NodeCanopen402Driver : public NodeCanopenProxyDriver<NODETYPE>
const std_srvs::srv::Trigger::Request::SharedPtr request,
std_srvs::srv::Trigger::Response::SharedPtr response);

/**
* @brief Method to set cyclic torque mode
*
* Calls Motor402::enterModeAndWait with Profiled Torque Mode as
* Target Operation Mode. If successful, the motor was transitioned
* to Profiled Torque Mode.
*
* @param [in] void
*
* @return bool
*/
bool set_mode_cyclic_torque();

/**
* @brief Service Callback to set target
*
Expand Down
Loading

0 comments on commit f1fef24

Please sign in to comment.