joint_trajectory_action.h
Go to the documentation of this file.
00001 /******************************************************************************
00002  * Copyright (c) 2011
00003  * GPS GmbH
00004  *
00005  * Author:
00006  * Alexey Zakharov
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 GPS GmbH 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 #ifndef JOINTTRAJECTORYACTION_H
00041 #define JOINTTRAJECTORYACTION_H
00042 
00043 #include <ros/ros.h>
00044 #include <control_msgs/FollowJointTrajectoryAction.h>
00045 #include <sensor_msgs/JointState.h>
00046 #include <actionlib/server/simple_action_server.h>
00047 #include <brics_actuator/JointPositions.h>
00048 #include <brics_actuator/JointVelocities.h>
00049 
00050 namespace KDL
00051 {
00052 class Trajectory_Composite;
00053 }
00054 
00055 typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> Server;
00056 
00057 class JointStateObserver;
00058 
00059 class JointTrajectoryAction
00060 {
00061 public:
00062   JointTrajectoryAction(JointStateObserver* jointStateObserver);
00063   JointTrajectoryAction(JointStateObserver* youbot, double velocityGain, double positionGain, double frequency);
00064   JointTrajectoryAction(const JointTrajectoryAction& orig);
00065   virtual ~JointTrajectoryAction();
00066 
00067   void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server* as);
00068 
00069   void jointStateCallback(const sensor_msgs::JointState& joint_state);
00070   void jointStateCallback(const brics_actuator::JointPositions& position,
00071                           const brics_actuator::JointVelocities& velocity);
00072 
00073   void setVelocityGain(double velocityGain);
00074   double getVelocityGain() const;
00075 
00076   void setPositionGain(double positionGain);
00077   double getPositionGain() const;
00078 
00079   void setFrequency(double frequency);
00080   double getFrequency() const;
00081 
00082 private:
00083 
00084   double velocityGain;
00085   double positionGain;
00086   double frequency;
00087 
00088   sensor_msgs::JointState current_state;
00089   JointStateObserver* jointStateObserver;
00090 
00091 private:
00092 
00093   double calculateVelocity(double actualAngle, double actualVelocity,
00094                            const KDL::Trajectory_Composite& trajectoryComposite, double elapsedTimeInSec);
00095 
00096   void controlLoop(const std::vector<double>& actualJointAngles, const std::vector<double>& actualJointVelocities,
00097                    const KDL::Trajectory_Composite* trajectoryComposite, int numberOfJoints, ros::Time startTime,
00098                    std::vector<double>& velocities);
00099 
00100   void setTargetTrajectory(double angle1, double angle2, double duration,
00101                            KDL::Trajectory_Composite& trajectoryComposite);
00102 
00103 };
00104 
00105 #endif  /* JOINTTRAJECTORYACTION_H */
00106 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


youbot_oodl
Author(s): Sebastian Blumenthal
autogenerated on Fri Jul 26 2013 12:00:42