32 #include <sr_robot_msgs/UBI0All.h> 33 #include <sr_robot_msgs/UBI0.h> 34 #include <sr_robot_msgs/AuxSpiData.h> 35 #include <sr_robot_msgs/MidProxDataAll.h> 36 #include <sr_robot_msgs/MidProxData.h> 44 template<
class StatusType,
class CommandType>
49 UBI0(
ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
52 UBI0(
ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
59 void init(std::vector<generic_updater::UpdateConfig> update_configs_vector,
69 virtual void update(StatusType *status_data);
81 virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
107 class UBI0<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> :
109 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>
112 UBI0(
ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
115 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
117 ROS_ERROR(
"This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
120 UBI0(
ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
124 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
126 ROS_ERROR(
"This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
135 class UBI0<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND> :
137 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>
140 UBI0(
ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
143 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
145 ROS_ERROR(
"This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
148 UBI0(
ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
152 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
154 ROS_ERROR(
"This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
163 class UBI0<ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_COMMAND> :
165 ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_COMMAND>
168 UBI0(
ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
171 ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
173 ROS_ERROR(
"This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
176 UBI0(
ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
180 ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
182 ROS_ERROR(
"This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector< GenericTactileData > > init_tactiles_vector)
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
virtual std::vector< AllTactileData > * get_tactile_data()
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
virtual void update(StatusType *status_data)
void init(std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
boost::shared_ptr< UBI0PalmData > palm_tactiles
the object containing the data from the palm sensors
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::AuxSpiData > > aux_spi_publisher
boost::shared_ptr< std::vector< UBI0Data > > tactiles_vector
the vector containing the data for the tactiles.
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector< GenericTactileData > > init_tactiles_vector)
virtual void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector< GenericTactileData > > init_tactiles_vector)