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 #ifndef _wam_driver_h_
00026 #define _wam_driver_h_
00027
00028 #include <iri_base_driver/iri_base_driver.h>
00029 #include <iri_wam_wrapper/WamConfig.h>
00030 #include <trajectory_msgs/JointTrajectory.h>
00031 #include <geometry_msgs/Pose.h>
00032
00033
00034
00035
00036
00037 struct ForceRequest
00038 {
00039 enum Tstatus {
00040 QUIET,
00041 ONGOING,
00042 FAILED,
00043 SUCCESS
00044 };
00045
00046 Tstatus status;
00047 double force_value;
00048
00049 void init()
00050 {
00051 status = QUIET;
00052 force_value = 0.0;
00053 }
00054
00055 void success_response(double v)
00056 {
00057 status = SUCCESS;
00058 force_value = v;
00059 }
00060
00061 bool is_estimate_force_request_finish()
00062 {
00063 return (status != ONGOING);
00064 }
00065
00066 bool was_estimate_force_request_succedded()
00067 {
00068 return (status == SUCCESS);
00069 }
00070 };
00071
00091 class WamDriver : public iri_base_driver::IriBaseDriver
00092 {
00093 private:
00094
00095 std::string robot_name_;
00096 std::string wamserver_ip;
00097 int server_port;
00098 int state_refresh_rate;
00099 wamDriver *wam_;
00103 boost::shared_ptr<ForceRequest> force_request_;
00104
00105 trajectory_msgs::JointTrajectoryPoint desired_joint_trajectory_point_;
00106
00113 bool is_joints_move_request_valid(const std::vector<double> & angles);
00114
00115 public:
00122 typedef iri_wam_wrapper::WamConfig Config;
00123
00130 Config config_;
00131
00140 WamDriver();
00141
00152 bool openDriver(void);
00153
00164 bool closeDriver(void);
00165
00176 bool startDriver(void);
00177
00188 bool stopDriver(void);
00189
00201 void config_update(const Config& new_cfg, uint32_t level=0);
00202
00203
00204
00205
00212 ~WamDriver();
00213 std::string get_robot_name();
00214 int get_num_joints();
00215
00219 bool is_moving();
00220 bool is_joint_trajectory_result_succeeded();
00221 void wait_move_end();
00222 void get_pose(std::vector<double> *pose);
00223 void get_joint_angles(std::vector<double> *angles);
00224 void move_in_joints(std::vector<double> *angles, std::vector<double>* vels = NULL, std::vector<double>* accs = NULL);
00225 void hold_current_position(bool on);
00232 void move_in_cartesian_pose(const geometry_msgs::Pose pose, const double vel = 0, const double acc = 0);
00233
00238 trajectory_msgs::JointTrajectoryPoint get_desired_joint_trajectory_point();
00239
00247 void move_trajectory_in_joints(const trajectory_msgs::JointTrajectory & trajectory);
00248
00249 void stop_trajectory_in_joints();
00250
00264 void move_trajectory_learnt_and_estimate_force(const std::string model_filename,
00265 const std::string points_filename);
00266
00270 const boost::shared_ptr<ForceRequest> get_force_request_info()
00271 {
00272 return force_request_;
00273 }
00274
00278 void start_dmp_tracker(const std::vector<double> * initial, const std::vector<double> * goal);
00279
00280 void dmp_tracker_new_goal(const std::vector<double> * new_goal);
00281
00282 void jnt_pos_cmd_callback(const std::vector<float> * joints,
00283 const std::vector<float> * rate_limits);
00284 };
00285
00286 #endif