youbot_arm_test.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002 * Copyright (c) 2011
00003 * Locomotec
00004 *
00005 * Author:
00006 * Sebastian Blumenthal
00007 *
00008 *
00009 * This software is published under a dual-license: GNU Lesser General Public
00010 * License LGPL 2.1 and BSD license. The dual-license implies that users of this
00011 * code may choose which terms they prefer.
00012 *
00013 * Redistribution and use in source and binary forms, with or without
00014 * modification, are permitted provided that the following conditions are met:
00015 *
00016 * * Redistributions of source code must retain the above copyright
00017 * notice, this list of conditions and the following disclaimer.
00018 * * Redistributions in binary form must reproduce the above copyright
00019 * notice, this list of conditions and the following disclaimer in the
00020 * documentation and/or other materials provided with the distribution.
00021 * * Neither the name of Locomotec nor the names of its
00022 * contributors may be used to endorse or promote products derived from
00023 * this software without specific prior written permission.
00024 *
00025 * This program is free software: you can redistribute it and/or modify
00026 * it under the terms of the GNU Lesser General Public License LGPL as
00027 * published by the Free Software Foundation, either version 2.1 of the
00028 * License, or (at your option) any later version or the BSD license.
00029 *
00030 * This program is distributed in the hope that it will be useful,
00031 * but WITHOUT ANY WARRANTY; without even the implied warranty of
00032 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00033 * GNU Lesser General Public License LGPL and the BSD license for more details.
00034 *
00035 * You should have received a copy of the GNU Lesser General Public
00036 * License LGPL and BSD license along with this program.
00037 *
00038 ******************************************************************************/
00039 
00040 #include <iostream>
00041 #include <assert.h>
00042 
00043 #include <ros/ros.h>
00044 #include <trajectory_msgs/JointTrajectory.h>
00045 #include <brics_actuator/CartesianWrench.h>
00046 
00047 #include <boost/units/io.hpp>
00048 
00049 #include <boost/units/systems/angle/degrees.hpp>
00050 #include <boost/units/conversion.hpp>
00051 
00052 #include <iostream>
00053 #include <assert.h>
00054 
00055 
00056 #include <ros/ros.h>
00057 #include <brics_actuator/JointPositions.h>
00058 
00059 #include <boost/units/systems/si/length.hpp>
00060 #include <boost/units/systems/si/plane_angle.hpp>
00061 #include <boost/units/io.hpp>
00062 
00063 #include <boost/units/systems/angle/degrees.hpp>
00064 #include <boost/units/conversion.hpp>
00065 
00066 using namespace std;
00067 
00068 int main(int argc, char **argv) {
00069 
00070         ros::init(argc, argv, "youbot_arm_test");
00071         ros::NodeHandle n;
00072         ros::Publisher armPositionsPublisher;
00073         ros::Publisher gripperPositionPublisher;
00074 
00075         armPositionsPublisher = n.advertise<brics_actuator::JointPositions > ("arm_1/arm_controller/position_command", 1);
00076         gripperPositionPublisher = n.advertise<brics_actuator::JointPositions > ("arm_1/gripper_controller/position_command", 1);
00077 
00078         ros::Rate rate(20); //Hz
00079         double readValue;
00080         static const int numberOfArmJoints = 5;
00081         static const int numberOfGripperJoints = 2;
00082         while (n.ok()) {
00083                 brics_actuator::JointPositions command;
00084                 vector <brics_actuator::JointValue> armJointPositions;
00085                 vector <brics_actuator::JointValue> gripperJointPositions;
00086 
00087                 armJointPositions.resize(numberOfArmJoints); //TODO:change that
00088                 gripperJointPositions.resize(numberOfGripperJoints);
00089 
00090                 std::stringstream jointName;
00091 
00092 
00093                 // ::io::base_unit_info <boost::units::si::angular_velocity>).name();
00094                 for (int i = 0; i < numberOfArmJoints; ++i) {
00095                         cout << "Please type in value for joint " << i + 1 << endl;
00096                         cin >> readValue;
00097 
00098                         jointName.str("");
00099                         jointName << "arm_joint_" << (i + 1);
00100 
00101                         armJointPositions[i].joint_uri = jointName.str();
00102                         armJointPositions[i].value = readValue;
00103 
00104                         armJointPositions[i].unit = boost::units::to_string(boost::units::si::radians);
00105                         cout << "Joint " << armJointPositions[i].joint_uri << " = " << armJointPositions[i].value << " " << armJointPositions[i].unit << endl;
00106 
00107                 };
00108 
00109                 cout << "Please type in value for a left jaw of the gripper " << endl;
00110                 cin >> readValue;
00111                 gripperJointPositions[0].joint_uri = "gripper_finger_joint_l";
00112                 gripperJointPositions[0].value = readValue;
00113                 gripperJointPositions[0].unit = boost::units::to_string(boost::units::si::meter);
00114 
00115                 cout << "Please type in value for a right jaw of the gripper " << endl;
00116                 cin >> readValue;
00117                 gripperJointPositions[1].joint_uri = "gripper_finger_joint_r";
00118                 gripperJointPositions[1].value = readValue;
00119                 gripperJointPositions[1].unit = boost::units::to_string(boost::units::si::meter);
00120 
00121                 cout << "sending command ..." << endl;
00122 
00123                 command.positions = armJointPositions;
00124                 armPositionsPublisher.publish(command);
00125 
00126                 command.positions = gripperJointPositions;
00127         gripperPositionPublisher.publish(command);
00128 
00129                 cout << "--------------------" << endl;
00130                 rate.sleep();
00131 
00132         }
00133 
00134         return 0;
00135 }
00136 
00137 /* EOF */


youbot_oodl
Author(s): Sebastian Blumenthal
autogenerated on Mon Oct 6 2014 09:06:15