Public Member Functions | Private Member Functions | Private Attributes | List of all members
SchunkCanopenNode Class Reference

#include <SchunkCanopenNode.h>

Public Member Functions

 SchunkCanopenNode ()
 

Private Member Functions

void cancelCB (actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > gh)
 
bool closeBrakes (std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
 Close the brakes on all nodes. Use this when the device is standing still for a longer time to reduce hight motor currents for doing nothing. More...
 
bool enableNodes (std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
 This service call enables the devices after a fault, a quick stop or simply when the brakes have been closed by hand (via the close_brakes service call) More...
 
void goalCB (actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > gh)
 
bool homeAllNodes (schunk_canopen_driver::HomeAllRequest &req, schunk_canopen_driver::HomeAllResponse &resp)
 Perform a reset offset for all nodes. You should call this service, after driving the devices to their zero position manually. More...
 
bool homeNodesCanIds (schunk_canopen_driver::HomeWithIDsRequest &req, schunk_canopen_driver::HomeWithIDsResponse &resp)
 Perform a reset offset for a given list of nodes. You should call this service, after driving the device to it's zero position manually. Only the nodes given in the node list are affected by this service call. The position of all unlisted joints is irrelevant. More...
 
bool homeNodesJointNames (schunk_canopen_driver::HomeWithJointNamesRequest &req, schunk_canopen_driver::HomeWithJointNamesResponse &resp)
 Perform a reset offset for a given list of nodes. You should call this service, after driving the device to it's zero position manually. Only the nodes given in the node list are affected by this service call. The position of all unlisted joints is irrelevant. More...
 
void initDevices ()
 Function that actually initializes the devices. Will get called either on startup (if autostart is allowed) or by the init_devices service call. More...
 
bool initDevicesCb (std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
 Triggers initialization of the canopen devices. More...
 
bool quickStopNodes (std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
 Performs a quick stop on all nodes. You should prefer this service call to aborting the followJointTrajectory action, as this will instantaniously stop the robot's movement without resulting in a fault state. More...
 
void rosControlLoop ()
 When using ros_control this will perform the control loop in a separate thread. More...
 
void trajThread (actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > &gh)
 Control loop thread when not using ros_control. More...
 

Private Attributes

actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > m_action_server
 
std::vector< DS402Group::Ptrm_chain_handles
 
ros::ServiceServer m_close_brakes_service
 
CanOpenController::Ptr m_controller
 
boost::shared_ptr< controller_manager::ControllerManagerm_controller_manager
 
ros::Publisher m_current_pub
 
ros::ServiceServer m_enable_service
 
boost::shared_ptr< SchunkCanopenHardwareInterfacem_hardware_interface
 
bool m_has_goal
 
ros::ServiceServer m_home_service_all
 
ros::ServiceServer m_home_service_canopen_ids
 
ros::ServiceServer m_home_service_joint_names
 
bool m_homing_active
 
ros::ServiceServer m_init_service
 
bool m_is_enabled
 
std::map< std::string, uint8_tm_joint_name_mapping
 
ros::Publisher m_joint_pub
 
bool m_nodes_initialized
 
ds402::ProfilePositionModeConfiguration m_ppm_config
 
ros::NodeHandle m_priv_nh
 
ros::NodeHandle m_pub_nh
 
ros::ServiceServer m_quick_stop_service
 
boost::thread m_ros_control_thread
 
std::string m_traj_controller_name
 
boost::thread m_traj_thread
 
bool m_use_ros_control
 
bool m_was_disabled
 

Detailed Description

Definition at line 47 of file SchunkCanopenNode.h.

Constructor & Destructor Documentation

SchunkCanopenNode::SchunkCanopenNode ( )

Definition at line 37 of file SchunkCanopenNode.cpp.

Member Function Documentation

void SchunkCanopenNode::cancelCB ( actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction >  gh)
private

Definition at line 476 of file SchunkCanopenNode.cpp.

bool SchunkCanopenNode::closeBrakes ( std_srvs::TriggerRequest &  req,
std_srvs::TriggerResponse &  resp 
)
private

Close the brakes on all nodes. Use this when the device is standing still for a longer time to reduce hight motor currents for doing nothing.

Remember to call the enable_nodes service when you want to go on.

Definition at line 604 of file SchunkCanopenNode.cpp.

bool SchunkCanopenNode::enableNodes ( std_srvs::TriggerRequest &  req,
std_srvs::TriggerResponse &  resp 
)
private

This service call enables the devices after a fault, a quick stop or simply when the brakes have been closed by hand (via the close_brakes service call)

Definition at line 584 of file SchunkCanopenNode.cpp.

void SchunkCanopenNode::goalCB ( actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction >  gh)
private

Definition at line 314 of file SchunkCanopenNode.cpp.

bool SchunkCanopenNode::homeAllNodes ( schunk_canopen_driver::HomeAllRequest &  req,
schunk_canopen_driver::HomeAllResponse &  resp 
)
private

Perform a reset offset for all nodes. You should call this service, after driving the devices to their zero position manually.

Definition at line 653 of file SchunkCanopenNode.cpp.

bool SchunkCanopenNode::homeNodesCanIds ( schunk_canopen_driver::HomeWithIDsRequest &  req,
schunk_canopen_driver::HomeWithIDsResponse &  resp 
)
private

Perform a reset offset for a given list of nodes. You should call this service, after driving the device to it's zero position manually. Only the nodes given in the node list are affected by this service call. The position of all unlisted joints is irrelevant.

Note
: This service call exists for canopen IDs (usually 3-8 for a lwa4p) and as an interface using the joint names from the URDF.

Definition at line 691 of file SchunkCanopenNode.cpp.

bool SchunkCanopenNode::homeNodesJointNames ( schunk_canopen_driver::HomeWithJointNamesRequest &  req,
schunk_canopen_driver::HomeWithJointNamesResponse &  resp 
)
private

Perform a reset offset for a given list of nodes. You should call this service, after driving the device to it's zero position manually. Only the nodes given in the node list are affected by this service call. The position of all unlisted joints is irrelevant.

Note
: This service call exists for canopen IDs (usually 3-8 for a lwa4p) and as an interface using the joint names from the URDF.

Definition at line 667 of file SchunkCanopenNode.cpp.

void SchunkCanopenNode::initDevices ( )
private

Function that actually initializes the devices. Will get called either on startup (if autostart is allowed) or by the init_devices service call.

Definition at line 237 of file SchunkCanopenNode.cpp.

bool SchunkCanopenNode::initDevicesCb ( std_srvs::TriggerRequest &  req,
std_srvs::TriggerResponse &  resp 
)
private

Triggers initialization of the canopen devices.

This service will only be advertised when the autostart parameter is set to false. Otherwise initialization will be triggered automatically at startup.

Definition at line 228 of file SchunkCanopenNode.cpp.

bool SchunkCanopenNode::quickStopNodes ( std_srvs::TriggerRequest &  req,
std_srvs::TriggerResponse &  resp 
)
private

Performs a quick stop on all nodes. You should prefer this service call to aborting the followJointTrajectory action, as this will instantaniously stop the robot's movement without resulting in a fault state.

Definition at line 626 of file SchunkCanopenNode.cpp.

void SchunkCanopenNode::rosControlLoop ( )
private

When using ros_control this will perform the control loop in a separate thread.

Definition at line 503 of file SchunkCanopenNode.cpp.

void SchunkCanopenNode::trajThread ( actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > &  gh)
private

Control loop thread when not using ros_control.

Definition at line 348 of file SchunkCanopenNode.cpp.

Member Data Documentation

actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> SchunkCanopenNode::m_action_server
private

Definition at line 139 of file SchunkCanopenNode.h.

std::vector<DS402Group::Ptr> SchunkCanopenNode::m_chain_handles
private

Definition at line 154 of file SchunkCanopenNode.h.

ros::ServiceServer SchunkCanopenNode::m_close_brakes_service
private

Definition at line 141 of file SchunkCanopenNode.h.

CanOpenController::Ptr SchunkCanopenNode::m_controller
private

Definition at line 152 of file SchunkCanopenNode.h.

boost::shared_ptr<controller_manager::ControllerManager> SchunkCanopenNode::m_controller_manager
private

Definition at line 163 of file SchunkCanopenNode.h.

ros::Publisher SchunkCanopenNode::m_current_pub
private

Definition at line 149 of file SchunkCanopenNode.h.

ros::ServiceServer SchunkCanopenNode::m_enable_service
private

Definition at line 140 of file SchunkCanopenNode.h.

boost::shared_ptr<SchunkCanopenHardwareInterface> SchunkCanopenNode::m_hardware_interface
private

Definition at line 162 of file SchunkCanopenNode.h.

bool SchunkCanopenNode::m_has_goal
private

Definition at line 156 of file SchunkCanopenNode.h.

ros::ServiceServer SchunkCanopenNode::m_home_service_all
private

Definition at line 143 of file SchunkCanopenNode.h.

ros::ServiceServer SchunkCanopenNode::m_home_service_canopen_ids
private

Definition at line 145 of file SchunkCanopenNode.h.

ros::ServiceServer SchunkCanopenNode::m_home_service_joint_names
private

Definition at line 144 of file SchunkCanopenNode.h.

bool SchunkCanopenNode::m_homing_active
private

Definition at line 167 of file SchunkCanopenNode.h.

ros::ServiceServer SchunkCanopenNode::m_init_service
private

Definition at line 146 of file SchunkCanopenNode.h.

bool SchunkCanopenNode::m_is_enabled
private

Definition at line 166 of file SchunkCanopenNode.h.

std::map<std::string, uint8_t> SchunkCanopenNode::m_joint_name_mapping
private

Definition at line 155 of file SchunkCanopenNode.h.

ros::Publisher SchunkCanopenNode::m_joint_pub
private

Definition at line 148 of file SchunkCanopenNode.h.

bool SchunkCanopenNode::m_nodes_initialized
private

Definition at line 170 of file SchunkCanopenNode.h.

ds402::ProfilePositionModeConfiguration SchunkCanopenNode::m_ppm_config
private

Definition at line 169 of file SchunkCanopenNode.h.

ros::NodeHandle SchunkCanopenNode::m_priv_nh
private

Definition at line 54 of file SchunkCanopenNode.h.

ros::NodeHandle SchunkCanopenNode::m_pub_nh
private

Definition at line 55 of file SchunkCanopenNode.h.

ros::ServiceServer SchunkCanopenNode::m_quick_stop_service
private

Definition at line 142 of file SchunkCanopenNode.h.

boost::thread SchunkCanopenNode::m_ros_control_thread
private

Definition at line 158 of file SchunkCanopenNode.h.

std::string SchunkCanopenNode::m_traj_controller_name
private

Definition at line 172 of file SchunkCanopenNode.h.

boost::thread SchunkCanopenNode::m_traj_thread
private

Definition at line 157 of file SchunkCanopenNode.h.

bool SchunkCanopenNode::m_use_ros_control
private

Definition at line 160 of file SchunkCanopenNode.h.

bool SchunkCanopenNode::m_was_disabled
private

Definition at line 165 of file SchunkCanopenNode.h.


The documentation for this class was generated from the following files:


schunk_canopen_driver
Author(s): Felix Mauch , Georg Heppner
autogenerated on Mon Jun 10 2019 15:07:49