00001 #include "ros/ros.h"
00002 #include <kdl/jntarray.hpp>
00003 #include <sensor_msgs/JointState.h>
00004 #include <brics_actuator/JointVelocities.h>
00005 #include <trajectory_msgs/JointTrajectory.h>
00006
00007
00008 using namespace std;
00009 using namespace KDL;
00010
00011 KDL::JntArray VirtualQ;
00012 KDL::JntArray q;
00013
00014 ros::Time last;
00015 bool started = false;
00016
00017 ros::Publisher arm_pub_;
00018
00019 JntArray parseJointStates(std::vector<std::string> names, std::vector<double> positions)
00020 {
00021 JntArray q_temp(7);
00022 int count = 0;
00023 for(unsigned int i = 0; i < names.size(); i++)
00024 {
00025 if(strncmp(names[i].c_str(), "arm_", 4) == 0)
00026 {
00027 q_temp(count) = positions[i];
00028 count++;
00029 }
00030 }
00031 if(!started)
00032 {
00033 VirtualQ = q_temp;
00034 started = true;
00035 last = ros::Time::now();
00036
00037 ROS_INFO("Starting up controller with first configuration");
00038 }
00039 return q_temp;
00040 }
00041
00042
00043 void sendVel(JntArray q_dot)
00044 {
00045 ros::Time now = ros::Time::now();
00046 double dt = now.toSec() - last.toSec();
00047 last = now;
00048 double horizon = 3.0*dt;
00049
00050
00051 trajectory_msgs::JointTrajectory traj;
00052 traj.header.stamp = ros::Time::now()+ros::Duration(0.01);
00053 traj.joint_names.push_back("arm_1_joint");
00054 traj.joint_names.push_back("arm_2_joint");
00055 traj.joint_names.push_back("arm_3_joint");
00056 traj.joint_names.push_back("arm_4_joint");
00057 traj.joint_names.push_back("arm_5_joint");
00058 traj.joint_names.push_back("arm_6_joint");
00059 traj.joint_names.push_back("arm_7_joint");
00060
00061 traj.points.resize(1);
00062 bool nonzero = false;
00063 for(int i = 0; i < 7; i++)
00064 {
00065 if(q_dot(i) != 0.0)
00066 {
00067 traj.points[0].positions.push_back(VirtualQ(i) + q_dot(i)*horizon);
00068 traj.points[0].velocities.push_back(q_dot(i));
00069 VirtualQ(i) += q_dot(i)*dt;
00070 nonzero = true;
00071 }
00072 }
00073 traj.points[0].time_from_start = ros::Duration(horizon);
00074 if(nonzero)
00075 arm_pub_.publish(traj);
00076 }
00077
00078 void controllerStateCallback(const sensor_msgs::JointState::ConstPtr& msg)
00079 {
00080 std::vector<std::string> names = msg->name;
00081 std::vector<double> positions = msg->position;
00082 q = parseJointStates(names,positions);
00083 }
00084
00085 void velocityCallback(const brics_actuator::JointVelocities::ConstPtr& msg)
00086 {
00087 KDL::JntArray q_dot;
00088 q_dot.resize(7);
00089 for(unsigned int j = 0; j < 7; j++)
00090 {
00091 q_dot(j) = msg->velocities.at(j).value;
00092 }
00093 sendVel(q_dot);
00094
00095 }
00096
00097
00098 int main(int argc, char **argv)
00099 {
00100 ros::init(argc, argv, "cob_simulation_tester");
00101 ros::NodeHandle n;
00102 arm_pub_ = n.advertise<trajectory_msgs::JointTrajectory>("/arm_controller/command",1);
00103 ros::Subscriber sub = n.subscribe("/joint_states", 1, controllerStateCallback);
00104 ros::Subscriber sub_vc = n.subscribe("/arm_controller/command_vel", 1, velocityCallback);
00105 ros::spin();
00106
00107 return 0;
00108 }