32 #include <std_msgs/Float64MultiArray.h> 33 #include <trajectory_msgs/JointTrajectory.h> 34 #include <sensor_msgs/JointState.h> 35 #include <control_msgs/FollowJointTrajectoryAction.h> 36 #include <control_msgs/JointTrajectoryControllerState.h> 37 #include <schunk_sdh/TactileSensor.h> 38 #include <schunk_sdh/TactileMatrix.h> 39 #include <schunk_sdh/TemperatureArray.h> 40 #include <schunk_sdh/PressureArrayList.h> 43 #include <std_srvs/Trigger.h> 44 #include <cob_srvs/SetString.h> 47 #include <diagnostic_msgs/DiagnosticArray.h> 50 #include <schunk_sdh/sdh.h> 51 #include <schunk_sdh/dsa.h> 95 std::vector<SDH::cSDH::eAxisState>
state_;
115 trajectory_msgs::JointTrajectory
traj_;
141 topicPub_Diagnostics_ = nh_.
advertise<diagnostic_msgs::DiagnosticArray>(
"/diagnostics", 1);
149 if (isDSAInitialized_)
162 isInitialized_ =
false;
163 isDSAInitialized_ =
false;
167 topicPub_JointState_ = nh_.
advertise<sensor_msgs::JointState>(
"joint_states", 1);
168 topicPub_ControllerState_ = nh_.
advertise<control_msgs::JointTrajectoryControllerState>(
169 "joint_trajectory_controller/state", 1);
170 topicPub_TactileSensor_ = nh_.
advertise<schunk_sdh::TactileSensor>(
"tactile_data", 1);
171 topicPub_Temperature_ = nh_.
advertise<schunk_sdh::TemperatureArray>(
"temperature", 1);
172 topicPub_Pressure_ = nh_.
advertise<schunk_sdh::PressureArrayList>(
"pressure", 1);
175 sdh_ =
new SDH::cSDH(
false,
false, 0);
189 subSetVelocitiesRaw_ = nh_.
subscribe(
"joint_group_velocity_controller/command", 1,
193 nh_.
param(
"sdhdevicetype", sdhdevicetype_, std::string(
"PCAN"));
194 nh_.
param(
"sdhdevicestring", sdhdevicestring_, std::string(
"/dev/pcan0"));
195 nh_.
param(
"sdhdevicenum", sdhdevicenum_, 0);
197 nh_.
param(
"dsadevicestring", dsadevicestring_, std::string(
""));
198 nh_.
param(
"dsadevicenum", dsadevicenum_, 0);
199 nh_.
param(
"dsa_dbg_level", dsa_dbg_level_, 0);
200 nh_.
param(
"dsa_sensitivity", dsa_sensitivity_, 0.5);
201 nh_.
param(
"dsa_calib_pressure", dsa_calib_pressure_, 0.000473);
202 nh_.
param(
"dsa_calib_voltage", dsa_calib_voltage_, 592.1);
204 nh_.
param(
"baudrate", baudrate_, 1000000);
205 nh_.
param(
"timeout", timeout_, static_cast<double>(0.04));
206 nh_.
param(
"id_read", id_read_, 43);
207 nh_.
param(
"id_write", id_write_, 42);
210 ROS_INFO(
"getting joint_names from parameter server");
214 nh_.
getParam(
"joint_names", joint_names_param);
218 ROS_ERROR(
"Parameter joint_names not set, shutting down node...");
222 DOF_ = joint_names_param.
size();
223 joint_names_.resize(DOF_);
224 for (
int i = 0; i <
DOF_; i++)
226 joint_names_[i] = (std::string)joint_names_param[i];
228 std::cout <<
"joint_names = " << joint_names_param << std::endl;
232 velocities_.resize(DOF_);
233 for (
int i = 0; i <
DOF_; i++)
239 state_.resize(axes_.size());
241 nh_.
param(
"OperationMode", operationMode_, std::string(
"position"));
256 if (mode ==
"position")
258 sdh_->SetController(SDH::cSDH::eCT_POSE);
260 else if (mode ==
"velocity")
262 sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
269 sdh_->SetAxisEnable(sdh_->All, 1.0);
271 catch (SDH::cSDHLibraryException* e)
273 ROS_ERROR(
"An exception was caught: %s", e->what());
278 operationMode_ = mode;
288 void executeCB(
const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
291 if (operationMode_ !=
"position")
293 ROS_ERROR(
"%s: Rejected, sdh not in position mode", action_name_.c_str());
299 ROS_ERROR(
"%s: Rejected, sdh not initialized", action_name_.c_str());
304 if (goal->trajectory.points.empty() || goal->trajectory.points[0].positions.size() != size_t(DOF_))
306 ROS_ERROR(
"%s: Rejected, malformed FollowJointTrajectoryGoal", action_name_.c_str());
310 while (hasNewGoal_ ==
true)
313 std::map<std::string, int> dict;
314 for (
int idx = 0; idx < goal->trajectory.joint_names.size(); idx++)
316 dict[goal->trajectory.joint_names[idx]] = idx;
319 targetAngles_.resize(DOF_);
320 targetAngles_[0] = goal->trajectory.points[0].positions[dict[
"sdh_knuckle_joint"]] * 180.0 /
pi_;
321 targetAngles_[1] = goal->trajectory.points[0].positions[dict[
"sdh_finger_22_joint"]] * 180.0 /
pi_;
322 targetAngles_[2] = goal->trajectory.points[0].positions[dict[
"sdh_finger_23_joint"]] * 180.0 /
pi_;
323 targetAngles_[3] = goal->trajectory.points[0].positions[dict[
"sdh_thumb_2_joint"]] * 180.0 /
pi_;
324 targetAngles_[4] = goal->trajectory.points[0].positions[dict[
"sdh_thumb_3_joint"]] * 180.0 /
pi_;
325 targetAngles_[5] = goal->trajectory.points[0].positions[dict[
"sdh_finger_12_joint"]] * 180.0 /
pi_;
326 targetAngles_[6] = goal->trajectory.points[0].positions[dict[
"sdh_finger_13_joint"]] * 180.0 /
pi_;
328 "received position goal: [['sdh_knuckle_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint']] = [%f,%f,%f,%f,%f,%f,%f]",
329 goal->trajectory.points[0].positions[dict[
"sdh_knuckle_joint"]],
330 goal->trajectory.points[0].positions[dict[
"sdh_thumb_2_joint"]],
331 goal->trajectory.points[0].positions[dict[
"sdh_thumb_3_joint"]],
332 goal->trajectory.points[0].positions[dict[
"sdh_finger_12_joint"]],
333 goal->trajectory.points[0].positions[dict[
"sdh_finger_13_joint"]],
334 goal->trajectory.points[0].positions[dict[
"sdh_finger_22_joint"]],
335 goal->trajectory.points[0].positions[dict[
"sdh_finger_23_joint"]]);
341 bool finished =
false;
342 while (finished ==
false)
346 ROS_WARN(
"%s: Aborted", action_name_.c_str());
350 for (
unsigned int i = 0; i < state_.size(); i++)
352 ROS_DEBUG(
"state[%d] = %d", i, state_[i]);
368 ROS_INFO(
"%s: Succeeded", action_name_.c_str());
379 ROS_ERROR(
"%s: Rejected, sdh not initialized", action_name_.c_str());
382 if (velocities->data.size() != velocities_.size())
384 ROS_ERROR(
"Velocity array dimension mismatch");
387 if (operationMode_ !=
"velocity")
389 ROS_ERROR(
"%s: Rejected, sdh not in velocity mode", action_name_.c_str());
394 while (hasNewGoal_ ==
true)
397 velocities_[0] = velocities->data[0] * 180.0 /
pi_;
398 velocities_[1] = velocities->data[5] * 180.0 /
pi_;
399 velocities_[2] = velocities->data[6] * 180.0 /
pi_;
400 velocities_[3] = velocities->data[1] * 180.0 /
pi_;
401 velocities_[4] = velocities->data[2] * 180.0 /
pi_;
402 velocities_[5] = velocities->data[3] * 180.0 /
pi_;
403 velocities_[6] = velocities->data[4] * 180.0 /
pi_;
417 if (isInitialized_ ==
false)
423 if (sdhdevicetype_.compare(
"RS232") == 0)
425 sdh_->OpenRS232(sdhdevicenum_, 115200, 1, sdhdevicestring_.c_str());
426 ROS_INFO(
"Initialized RS232 for SDH");
427 isInitialized_ =
true;
429 else if (sdhdevicetype_.compare(
"PCAN") == 0)
431 ROS_INFO(
"Starting initializing PEAKCAN");
432 sdh_->OpenCAN_PEAK(baudrate_, timeout_, id_read_, id_write_, sdhdevicestring_.c_str());
433 ROS_INFO(
"Initialized PEAK CAN for SDH");
434 isInitialized_ =
true;
436 else if (sdhdevicetype_.compare(
"ESD") == 0)
438 ROS_INFO(
"Starting initializing ESD");
439 if (strcmp(sdhdevicestring_.c_str(),
"/dev/can0") == 0)
441 ROS_INFO(
"Initializing ESD on device %s", sdhdevicestring_.c_str());
442 sdh_->OpenCAN_ESD(0, baudrate_, timeout_, id_read_, id_write_);
444 else if (strcmp(sdhdevicestring_.c_str(),
"/dev/can1") == 0)
446 ROS_INFO(
"Initializin ESD on device %s", sdhdevicestring_.c_str());
447 sdh_->OpenCAN_ESD(1, baudrate_, timeout_, id_read_, id_write_);
451 ROS_ERROR(
"Currently only support for /dev/can0 and /dev/can1");
453 res.message =
"Currently only support for /dev/can0 and /dev/can1";
456 ROS_INFO(
"Initialized ESDCAN for SDH");
457 isInitialized_ =
true;
461 ROS_ERROR(
"Unknown SDH device type: %s", sdhdevicetype_.c_str());
466 catch (SDH::cSDHLibraryException* e)
468 ROS_ERROR(
"An exception was caught: %s", e->what());
470 res.message = e->what();
476 if (!dsadevicestring_.empty())
480 dsa_ =
new SDH::cDSA(dsa_dbg_level_, dsadevicenum_, dsadevicestring_.c_str());
482 dsa_->SetFramerate(1,
true);
483 ROS_INFO(
"Initialized RS232 for DSA Tactile Sensors on device %s", dsadevicestring_.c_str());
484 for(
int imat=0; imat<dsa_->GetSensorInfo().nb_matrices; imat++) {
485 dsa_->SetMatrixSensitivity(imat, dsa_sensitivity_);
487 isDSAInitialized_ =
true;
489 catch (SDH::cSDHLibraryException* e)
491 isDSAInitialized_ =
false;
492 ROS_ERROR(
"An exception was caught: %s", e->what());
494 res.message = e->what();
502 res.message =
"Could not set operation mode to '" + operationMode_ +
"'";
508 ROS_WARN(
"...sdh already initialized...");
510 res.message =
"sdh already initialized";
514 res.message =
"SDH initialised";
534 catch (SDH::cSDHLibraryException* e)
536 ROS_ERROR(
"An exception was caught: %s", e->what());
540 ROS_INFO(
"Stopping sdh succesfull");
542 res.message =
"stopped SDH";
557 ROS_INFO(
"Set operation mode to [%s]", req.data.c_str());
558 operationMode_ = req.data;
560 res.message =
"Set operation mode to "+req.data;
561 if (operationMode_ ==
"position")
563 sdh_->SetController(SDH::cSDH::eCT_POSE);
565 else if (operationMode_ ==
"velocity")
569 sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
570 sdh_->SetAxisEnable(sdh_->All, 1.0);
572 catch (SDH::cSDHLibraryException* e)
574 ROS_ERROR(
"An exception was caught: %s", e->what());
594 isInitialized_ =
false;
595 sdh_->EmergencyStop();
596 sdh_->SetAxisEnable(sdh_->All, 0.0);
597 sdh_->SetAxisMotorCurrent(sdh_->All, 0.0);
599 catch(
const SDH::cSDHLibraryException* e) {
600 ROS_ERROR(
"An exception was caught: %s", e->what());
602 res.message = e->what();
607 res.message =
"EMERGENCY stop";
620 isInitialized_ =
false;
621 isDSAInitialized_ =
false;
623 sdh_->SetAxisEnable(sdh_->All, 0.0);
624 sdh_->SetAxisMotorCurrent(sdh_->All, 0.0);
629 catch(
const SDH::cSDHLibraryException* e) {
630 ROS_ERROR(
"An exception was caught: %s", e->what());
632 res.message = e->what();
638 res.message =
"disconnected from SDH";
649 sdh_->SetAxisEnable(sdh_->All, 1.0);
650 sdh_->SetAxisMotorCurrent(sdh_->All, 0.5);
652 catch (
const SDH::cSDHLibraryException* e) {
653 ROS_ERROR(
"An exception was caught: %s", e->what());
655 res.message = e->what();
660 res.message =
"Motor ON";
671 sdh_->SetAxisEnable(sdh_->All, 0.0);
672 sdh_->SetAxisMotorCurrent(sdh_->All, 0.0);
674 catch (
const SDH::cSDHLibraryException* e) {
675 ROS_ERROR(
"An exception was caught: %s", e->what());
677 res.message = e->what();
682 res.message =
"Motor OFF";
695 if (isInitialized_ ==
true)
697 if (hasNewGoal_ ==
true)
704 catch (SDH::cSDHLibraryException* e)
706 ROS_ERROR(
"An exception was caught: %s", e->what());
710 if (operationMode_ ==
"position")
712 ROS_DEBUG(
"moving sdh in position mode");
716 sdh_->SetAxisTargetAngle(axes_, targetAngles_);
717 sdh_->MoveHand(
false);
719 catch (SDH::cSDHLibraryException* e)
721 ROS_ERROR(
"An exception was caught: %s", e->what());
725 else if (operationMode_ ==
"velocity")
727 ROS_DEBUG(
"moving sdh in velocity mode");
730 sdh_->SetAxisTargetVelocity(axes_, velocities_);
733 catch (SDH::cSDHLibraryException* e)
735 ROS_ERROR(
"An exception was caught: %s", e->what());
739 else if (operationMode_ ==
"effort")
743 ROS_WARN(
"Moving in effort mode currently disabled");
747 ROS_ERROR(
"sdh neither in position nor in velocity nor in effort mode. OperationMode = [%s]",
748 operationMode_.c_str());
755 std::vector<double> actualAngles;
758 actualAngles = sdh_->GetAxisActualAngle(axes_);
760 catch (SDH::cSDHLibraryException* e)
762 ROS_ERROR(
"An exception was caught: %s", e->what());
765 std::vector<double> actualVelocities;
768 actualVelocities = sdh_->GetAxisActualVelocity(axes_);
770 catch (SDH::cSDHLibraryException* e)
772 ROS_ERROR(
"An exception was caught: %s", e->what());
776 ROS_DEBUG(
"received %d angles from sdh", static_cast<int>(actualAngles.size()));
779 sensor_msgs::JointState msg;
780 msg.header.stamp = time;
781 msg.name.resize(DOF_);
782 msg.position.resize(DOF_);
783 msg.velocity.resize(DOF_);
784 msg.effort.resize(DOF_);
789 msg.position[0] = actualAngles[0] * pi_ / 180.0;
790 msg.position[1] = actualAngles[3] * pi_ / 180.0;
791 msg.position[2] = actualAngles[4] * pi_ / 180.0;
792 msg.position[3] = actualAngles[5] * pi_ / 180.0;
793 msg.position[4] = actualAngles[6] * pi_ / 180.0;
794 msg.position[5] = actualAngles[1] * pi_ / 180.0;
795 msg.position[6] = actualAngles[2] * pi_ / 180.0;
797 msg.velocity[0] = actualVelocities[0] * pi_ / 180.0;
798 msg.velocity[1] = actualVelocities[3] * pi_ / 180.0;
799 msg.velocity[2] = actualVelocities[4] * pi_ / 180.0;
800 msg.velocity[3] = actualVelocities[5] * pi_ / 180.0;
801 msg.velocity[4] = actualVelocities[6] * pi_ / 180.0;
802 msg.velocity[5] = actualVelocities[1] * pi_ / 180.0;
803 msg.velocity[6] = actualVelocities[2] * pi_ / 180.0;
805 topicPub_JointState_.
publish(msg);
808 sensor_msgs::JointState mimicjointmsg;
809 mimicjointmsg.header.stamp = time;
810 mimicjointmsg.name.resize(1);
811 mimicjointmsg.position.resize(1);
812 mimicjointmsg.velocity.resize(1);
813 mimicjointmsg.name[0] =
"sdh_finger_21_joint";
814 mimicjointmsg.position[0] = msg.position[0];
815 mimicjointmsg.velocity[0] = msg.velocity[0];
816 topicPub_JointState_.
publish(mimicjointmsg);
819 control_msgs::JointTrajectoryControllerState controllermsg;
820 controllermsg.header.stamp = time;
821 controllermsg.joint_names.resize(DOF_);
822 controllermsg.desired.positions.resize(DOF_);
823 controllermsg.desired.velocities.resize(DOF_);
824 controllermsg.actual.positions.resize(DOF_);
825 controllermsg.actual.velocities.resize(DOF_);
826 controllermsg.error.positions.resize(DOF_);
827 controllermsg.error.velocities.resize(DOF_);
832 if (targetAngles_.size() != 0)
834 controllermsg.desired.positions[0] = targetAngles_[0] * pi_ / 180.0;
835 controllermsg.desired.positions[1] = targetAngles_[3] * pi_ / 180.0;
836 controllermsg.desired.positions[2] = targetAngles_[4] * pi_ / 180.0;
837 controllermsg.desired.positions[3] = targetAngles_[5] * pi_ / 180.0;
838 controllermsg.desired.positions[4] = targetAngles_[6] * pi_ / 180.0;
839 controllermsg.desired.positions[5] = targetAngles_[1] * pi_ / 180.0;
840 controllermsg.desired.positions[6] = targetAngles_[2] * pi_ / 180.0;
845 controllermsg.actual.positions = msg.position;
847 controllermsg.actual.velocities = msg.velocity;
849 for (
int i = 0; i <
DOF_; i++)
851 controllermsg.error.positions[i] = controllermsg.desired.positions[i] - controllermsg.actual.positions[i];
852 controllermsg.error.velocities[i] = controllermsg.desired.velocities[i] - controllermsg.actual.velocities[i];
855 topicPub_ControllerState_.
publish(controllermsg);
858 state_ = sdh_->GetAxisActualState(axes_);
861 schunk_sdh::TemperatureArray temp_array;
862 temp_array.header.stamp = time;
863 const std::vector<double> temp_value = sdh_->GetTemperature(sdh_->all_temperature_sensors);
864 if(temp_value.size()==temperature_names_.size()) {
866 temp_array.temperature = temp_value;
869 ROS_ERROR(
"amount of temperatures mismatch with stored names");
871 topicPub_Temperature_.
publish(temp_array);
878 diagnostic_msgs::DiagnosticArray diagnostics;
879 diagnostics.status.resize(1);
883 diagnostics.status[0].level = 2;
884 diagnostics.status[0].name =
"schunk_powercube_chain";
885 diagnostics.status[0].message =
"one or more drives are in Error mode";
891 diagnostics.status[0].level = 0;
893 if (isDSAInitialized_)
894 diagnostics.status[0].message =
"sdh with tactile sensing initialized and running";
896 diagnostics.status[0].message =
"sdh initialized and running, tactile sensors not connected";
900 diagnostics.status[0].level = 1;
902 diagnostics.status[0].message =
"sdh not initialized";
906 topicPub_Diagnostics_.
publish(diagnostics);
916 static const int dsa_reorder[6] = {2, 3, 4, 5, 0, 1};
919 if (isDSAInitialized_)
922 for (
int i = 0; i < 7; i++)
929 catch (SDH::cSDHLibraryException* e)
931 ROS_ERROR(
"An exception was caught: %s", e->what());
936 schunk_sdh::TactileSensor msg;
938 msg.tactile_matrix.resize(dsa_->GetSensorInfo().nb_matrices);
939 for (
int i = 0; i < dsa_->GetSensorInfo().nb_matrices; i++)
941 const int m = dsa_reorder[i];
942 schunk_sdh::TactileMatrix &tm = msg.tactile_matrix[i];
944 tm.cells_x = dsa_->GetMatrixInfo(m).cells_x;
945 tm.cells_y = dsa_->GetMatrixInfo(m).cells_y;
946 tm.tactile_array.resize(tm.cells_x * tm.cells_y);
947 for (uint y = 0; y < tm.cells_y; y++)
949 for (uint x = 0; x < tm.cells_x; x++)
950 tm.tactile_array[tm.cells_x * y + x] = dsa_->GetTexel(m, x, y);
954 topicPub_TactileSensor_.
publish(msg);
957 schunk_sdh::PressureArrayList msg_pressure_list;
959 const SDH::cDSA::sSensorInfo &sensor_info = dsa_->GetSensorInfo();
960 msg_pressure_list.pressure_list.resize(sensor_info.nb_matrices);
961 for(
const uint &fi : {0,1,2}) {
962 for(
const uint &part : {0,1}) {
964 const int mid = dsa_->GetMatrixIndex(fi, part);
965 msg_pressure_list.pressure_list[mid].sensor_name =
"sdh_"+finger_names_[fi]+std::to_string(part+2)+
"_link";
968 const SDH::cDSA::sMatrixInfo &matrix_info = dsa_->GetMatrixInfo(mid);
969 msg_pressure_list.pressure_list[mid].cells_x = matrix_info.cells_x;
970 msg_pressure_list.pressure_list[mid].cells_y = matrix_info.cells_y;
971 msg_pressure_list.pressure_list[mid].pressure.resize(matrix_info.cells_x * matrix_info.cells_y);
973 for (uint y(0); y < matrix_info.cells_y; y++) {
974 for (uint x(0); x < matrix_info.cells_x; x++) {
976 msg_pressure_list.pressure_list[mid].pressure[matrix_info.cells_x * y + x] =
977 dsa_->GetTexel(mid, x, y) * dsa_calib_pressure_ / dsa_calib_voltage_ * 1e6;
982 topicPub_Pressure_.
publish(msg_pressure_list);
989 "proximal_finger_1",
"distal_finger_1",
990 "proximal_finger_2",
"distal_finger_2",
991 "proximal_finger_3",
"distal_finger_3",
996 "finger_2",
"thumb_",
"finger_1" 1012 if (!sdh_node.
init())
1015 ROS_INFO(
"...sdh node running...");
1025 ROS_WARN(
"Parameter frequency not available, setting to default value: %f Hz", frequency);
1030 while (sdh_node.
nh_.
ok())
std::string sdhdevicetype_
static const std::vector< std::string > finger_names_
ros::ServiceServer srvServer_Init_
ros::Publisher topicPub_Pressure_
ros::Publisher topicPub_Temperature_
trajectory_msgs::JointTrajectory traj_
std::vector< SDH::cSDH::eAxisState > state_
void publish(const boost::shared_ptr< M > &message) const
bool srvCallback_EmergencyStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for emergency_stop.
ros::ServiceServer srvServer_MotorOff_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double dsa_calib_voltage_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool srvCallback_Disconnect(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for disconnect.
bool switchOperationMode(const std::string &mode)
Switches operation mode if possible.
ros::ServiceServer srvServer_EmergencyStop_
ROSCPP_DECL const std::string & getName()
std::string sdhdevicestring_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::string dsadevicestring_
ros::Publisher topicPub_JointState_
void updateDsa()
Main routine to update dsa.
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
int main(int argc, char **argv)
Main loop of ROS node.
ros::ServiceServer srvServer_SetOperationMode_
ros::ServiceServer srvServer_Disconnect_
SdhNode(std::string name)
Constructor for SdhNode class.
ros::ServiceServer srvServer_MotorOn_
bool srvCallback_MotorPowerOn(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Enable motor power.
std::string operationMode_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::ServiceServer srvServer_Recover_
const std::string & getNamespace() const
void executeCB(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
Executes the callback from the actionlib.
double dsa_calib_pressure_
ros::Publisher topicPub_TactileSensor_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
~SdhNode()
Destructor for SdhNode class.
actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > as_
bool srvCallback_MotorPowerOff(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Disable motor power.
void topicCallback_setVelocitiesRaw(const std_msgs::Float64MultiArrayPtr &velocities)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
bool init()
Initializes node to get parameters, subscribe and publish to topics.
std::vector< double > targetAngles_
std::vector< std::string > joint_names_
Implementation of ROS node for sdh.
bool getParam(const std::string &key, std::string &s) const
void updateSdh()
Main routine to update sdh.
ros::Subscriber subSetVelocitiesRaw_
ros::NodeHandle nh_
create a handle for this node, initialize node
bool srvCallback_Init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for init.
std::vector< double > velocities_
ros::Publisher topicPub_ControllerState_
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
static const std::vector< std::string > temperature_names_
ROSCPP_DECL void spinOnce()
bool srvCallback_Stop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for stop.
bool isNewGoalAvailable()
bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
Executes the service callback for set_operation_mode.
ros::Publisher topicPub_Diagnostics_
ros::ServiceServer srvServer_Stop_