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/TemperatureArray.h>
40 #include <std_srvs/Trigger.h>
41 #include <cob_srvs/SetString.h>
44 #include <diagnostic_msgs/DiagnosticArray.h>
47 #include <schunk_sdh/sdh.h>
89 std::vector<SDH::cSDH::eAxisState>
state_;
102 trajectory_msgs::JointTrajectory
traj_;
105 std::vector<int>
axes_;
151 "joint_trajectory_controller/state", 1);
156 sdh_ =
new SDH::cSDH(
false,
false, 0);
185 ROS_INFO(
"getting joint_names from parameter server");
193 ROS_ERROR(
"Parameter 'joint_names' not set, shutting down node...");
199 for (
int i = 0; i <
DOF_; i++)
203 std::cout <<
"joint_names = " << joint_names_param << std::endl;
208 for (
int i = 0; i <
DOF_; i++)
231 if (mode ==
"position")
233 sdh_->SetController(SDH::cSDH::eCT_POSE);
235 else if (mode ==
"velocity")
237 sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
244 sdh_->SetAxisEnable(
sdh_->All, 1.0);
246 catch (SDH::cSDHLibraryException* e)
248 ROS_ERROR(
"An exception was caught: %s", e->what());
263 void executeCB(
const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
279 if (goal->trajectory.points.empty() || goal->trajectory.points[0].positions.size() !=
size_t(
DOF_))
288 std::map<std::string, int> dict;
289 for (
int idx = 0; idx < goal->trajectory.joint_names.size(); idx++)
291 dict[goal->trajectory.joint_names[idx]] = idx;
295 targetAngles_[0] = goal->trajectory.points[0].positions[dict[
"sdh_knuckle_joint"]] * 180.0 /
pi_;
296 targetAngles_[1] = goal->trajectory.points[0].positions[dict[
"sdh_finger_22_joint"]] * 180.0 /
pi_;
297 targetAngles_[2] = goal->trajectory.points[0].positions[dict[
"sdh_finger_23_joint"]] * 180.0 /
pi_;
298 targetAngles_[3] = goal->trajectory.points[0].positions[dict[
"sdh_thumb_2_joint"]] * 180.0 /
pi_;
299 targetAngles_[4] = goal->trajectory.points[0].positions[dict[
"sdh_thumb_3_joint"]] * 180.0 /
pi_;
300 targetAngles_[5] = goal->trajectory.points[0].positions[dict[
"sdh_finger_12_joint"]] * 180.0 /
pi_;
301 targetAngles_[6] = goal->trajectory.points[0].positions[dict[
"sdh_finger_13_joint"]] * 180.0 /
pi_;
303 "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]",
304 goal->trajectory.points[0].positions[dict[
"sdh_knuckle_joint"]],
305 goal->trajectory.points[0].positions[dict[
"sdh_thumb_2_joint"]],
306 goal->trajectory.points[0].positions[dict[
"sdh_thumb_3_joint"]],
307 goal->trajectory.points[0].positions[dict[
"sdh_finger_12_joint"]],
308 goal->trajectory.points[0].positions[dict[
"sdh_finger_13_joint"]],
309 goal->trajectory.points[0].positions[dict[
"sdh_finger_22_joint"]],
310 goal->trajectory.points[0].positions[dict[
"sdh_finger_23_joint"]]);
316 bool finished =
false;
317 while (finished ==
false)
325 for (
unsigned int i = 0; i <
state_.size(); i++)
354 ROS_ERROR(
"Velocity array dimension mismatch");
396 ROS_INFO(
"Initialized RS232 for SDH");
401 ROS_INFO(
"Starting initializing PEAKCAN");
403 ROS_INFO(
"Initialized PEAK CAN for SDH");
408 ROS_INFO(
"Starting initializing ESD");
421 ROS_ERROR(
"Currently only support for /dev/can0 and /dev/can1");
423 res.message =
"Currently only support for /dev/can0 and /dev/can1";
426 ROS_INFO(
"Initialized ESDCAN for SDH");
430 catch (SDH::cSDHLibraryException* e)
432 ROS_ERROR(
"An exception was caught: %s", e->what());
434 res.message = e->what();
441 res.message =
"Could not set operation mode to '" +
operationMode_ +
"'";
447 ROS_WARN(
"...sdh already initialized...");
449 res.message =
"sdh already initialized";
472 catch (SDH::cSDHLibraryException* e)
474 ROS_ERROR(
"An exception was caught: %s", e->what());
478 ROS_INFO(
"Stopping sdh succesfull");
492 ROS_WARN(
"Service recover not implemented yet");
494 res.message =
"Service recover not implemented yet";
512 sdh_->SetController(SDH::cSDH::eCT_POSE);
518 sdh_->SetController(SDH::cSDH::eCT_VELOCITY);
519 sdh_->SetAxisEnable(
sdh_->All, 1.0);
521 catch (SDH::cSDHLibraryException* e)
523 ROS_ERROR(
"An exception was caught: %s", e->what());
544 sdh_->EmergencyStop();
545 sdh_->SetAxisEnable(
sdh_->All, 0.0);
546 sdh_->SetAxisMotorCurrent(
sdh_->All, 0.0);
548 catch(
const SDH::cSDHLibraryException* e) {
549 ROS_ERROR(
"An exception was caught: %s", e->what());
551 res.message = e->what();
556 res.message =
"EMERGENCY stop";
571 sdh_->SetAxisEnable(
sdh_->All, 0.0);
572 sdh_->SetAxisMotorCurrent(
sdh_->All, 0.0);
576 catch(
const SDH::cSDHLibraryException* e) {
577 ROS_ERROR(
"An exception was caught: %s", e->what());
579 res.message = e->what();
585 res.message =
"disconnected from SDH";
596 sdh_->SetAxisEnable(
sdh_->All, 1.0);
597 sdh_->SetAxisMotorCurrent(
sdh_->All, 0.5);
599 catch (
const SDH::cSDHLibraryException* e) {
600 ROS_ERROR(
"An exception was caught: %s", e->what());
602 res.message = e->what();
607 res.message =
"Motor ON";
618 sdh_->SetAxisEnable(
sdh_->All, 0.0);
619 sdh_->SetAxisMotorCurrent(
sdh_->All, 0.0);
621 catch (
const SDH::cSDHLibraryException* e) {
622 ROS_ERROR(
"An exception was caught: %s", e->what());
624 res.message = e->what();
629 res.message =
"Motor OFF";
650 catch (SDH::cSDHLibraryException* e)
652 ROS_ERROR(
"An exception was caught: %s", e->what());
658 ROS_DEBUG(
"moving sdh in position mode");
663 sdh_->MoveHand(
false);
665 catch (SDH::cSDHLibraryException* e)
667 ROS_ERROR(
"An exception was caught: %s", e->what());
673 ROS_DEBUG(
"moving sdh in velocity mode");
679 catch (SDH::cSDHLibraryException* e)
681 ROS_ERROR(
"An exception was caught: %s", e->what());
689 ROS_WARN(
"Moving in effort mode currently disabled");
693 ROS_ERROR(
"sdh neither in position nor in velocity nor in effort mode. OperationMode = [%s]",
701 std::vector<double> actualAngles;
704 actualAngles =
sdh_->GetAxisActualAngle(
axes_);
706 catch (SDH::cSDHLibraryException* e)
708 ROS_ERROR(
"An exception was caught: %s", e->what());
711 std::vector<double> actualVelocities;
714 actualVelocities =
sdh_->GetAxisActualVelocity(
axes_);
716 catch (SDH::cSDHLibraryException* e)
718 ROS_ERROR(
"An exception was caught: %s", e->what());
722 ROS_DEBUG(
"received %d angles from sdh",
static_cast<int>(actualAngles.size()));
727 sensor_msgs::JointState msg;
728 msg.header.stamp = time;
729 msg.name.resize(
DOF_);
730 msg.position.resize(
DOF_);
731 msg.velocity.resize(
DOF_);
732 msg.effort.resize(
DOF_);
737 msg.position[0] = actualAngles[0] *
pi_ / 180.0;
738 msg.position[1] = actualAngles[3] *
pi_ / 180.0;
739 msg.position[2] = actualAngles[4] *
pi_ / 180.0;
740 msg.position[3] = actualAngles[5] *
pi_ / 180.0;
741 msg.position[4] = actualAngles[6] *
pi_ / 180.0;
742 msg.position[5] = actualAngles[1] *
pi_ / 180.0;
743 msg.position[6] = actualAngles[2] *
pi_ / 180.0;
745 msg.velocity[0] = actualVelocities[0] *
pi_ / 180.0;
746 msg.velocity[1] = actualVelocities[3] *
pi_ / 180.0;
747 msg.velocity[2] = actualVelocities[4] *
pi_ / 180.0;
748 msg.velocity[3] = actualVelocities[5] *
pi_ / 180.0;
749 msg.velocity[4] = actualVelocities[6] *
pi_ / 180.0;
750 msg.velocity[5] = actualVelocities[1] *
pi_ / 180.0;
751 msg.velocity[6] = actualVelocities[2] *
pi_ / 180.0;
756 sensor_msgs::JointState mimicjointmsg;
757 mimicjointmsg.header.stamp = time;
758 mimicjointmsg.name.resize(1);
759 mimicjointmsg.position.resize(1);
760 mimicjointmsg.velocity.resize(1);
761 mimicjointmsg.name[0] =
"sdh_finger_21_joint";
762 mimicjointmsg.position[0] = msg.position[0];
763 mimicjointmsg.velocity[0] = msg.velocity[0];
767 control_msgs::JointTrajectoryControllerState controllermsg;
768 controllermsg.header.stamp = time;
769 controllermsg.joint_names.resize(
DOF_);
770 controllermsg.desired.positions.resize(
DOF_);
771 controllermsg.desired.velocities.resize(
DOF_);
772 controllermsg.actual.positions.resize(
DOF_);
773 controllermsg.actual.velocities.resize(
DOF_);
774 controllermsg.error.positions.resize(
DOF_);
775 controllermsg.error.velocities.resize(
DOF_);
793 controllermsg.actual.positions = msg.position;
795 controllermsg.actual.velocities = msg.velocity;
797 for (
int i = 0; i <
DOF_; i++)
799 controllermsg.error.positions[i] = controllermsg.desired.positions[i] - controllermsg.actual.positions[i];
800 controllermsg.error.velocities[i] = controllermsg.desired.velocities[i] - controllermsg.actual.velocities[i];
809 schunk_sdh::TemperatureArray temp_array;
810 temp_array.header.stamp = time;
811 const std::vector<double> temp_value =
sdh_->GetTemperature(
sdh_->all_temperature_sensors);
814 temp_array.temperature = temp_value;
817 ROS_ERROR(
"amount of temperatures mismatch with stored names");
826 diagnostic_msgs::DiagnosticArray diagnostics;
827 diagnostics.status.resize(1);
831 diagnostics.status[0].level = 2;
832 diagnostics.status[0].name =
"schunk_powercube_chain";
833 diagnostics.status[0].message =
"one or more drives are in Error mode";
839 diagnostics.status[0].level = 0;
841 diagnostics.status[0].message =
"sdh initialized and running";
845 diagnostics.status[0].level = 1;
847 diagnostics.status[0].message =
"sdh not initialized";
857 "proximal_finger_1",
"distal_finger_1",
858 "proximal_finger_2",
"distal_finger_2",
859 "proximal_finger_3",
"distal_finger_3",
869 int main(
int argc,
char** argv)
875 if (!sdh_node.
init())
888 ROS_WARN(
"Parameter frequency not available, setting to default value: %f Hz", frequency);
893 while (sdh_node.
nh_.
ok())