Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
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
00106