$search
00001 /* 00002 * test_app.cpp 00003 * 00004 * Created on: Feb 03, 2011 00005 * Author: Christian Bersch 00006 */ 00007 00008 00009 #include <ros/ros.h> 00010 00011 #include <simple_robot_control/robot_control.h> 00012 00013 00014 00015 00016 int main(int argc, char** argv){ 00017 00018 00019 00020 ros::init(argc, argv, "robot_control_test_app"); 00021 ros::NodeHandle nh; 00022 00023 //Create robot controller interface 00024 simple_robot_control::Robot robot; 00025 00026 //look straight 00027 robot.head.lookat("torso_lift_link", tf::Vector3(0.1, 0.0, 0.0)); 00028 00029 //do stuff with arms 00030 robot.left_arm.tuck(); 00031 robot.right_arm.stretch(); 00032 00033 double tuck_pos_right[] = { -0.4,0.0,0.0,-2.25,0.0,0.0,0.0, -0.01,1.35,-1.92,-1.68, 1.35,-0.18,0.31}; 00034 std::vector<double> tuck_pos_vec(tuck_pos_right, tuck_pos_right+14); 00035 robot.right_arm.goToJointPos(tuck_pos_vec); 00036 00037 robot.right_arm.stretch(); 00038 00039 00040 robot.right_arm.moveGripperToPosition(tf::Vector3(0.6,-0.1, 0.0), "torso_lift_link", simple_robot_control::Arm::FROM_ABOVE); 00041 robot.right_arm.moveGripperToPosition(tf::Vector3(0.8,-0.1, 0.1), "torso_lift_link", simple_robot_control::Arm::FRONTAL); 00042 00043 tf::StampedTransform tf_l (tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(0.8,0.1,0.0)), ros::Time::now(), "torso_lift_link","doesnt_matter"); 00044 robot.left_arm.moveGrippertoPose(tf_l); 00045 00046 //look at left gripper 00047 robot.head.lookat("l_gripper_tool_frame"); 00048 00049 //drive 0.5m forward 00050 robot.base.driveForward(0.5); 00051 00052 //raise torso to 10cm above lowest position 00053 robot.torso.move(0.1); 00054 00055 return 0; 00056 00057 }