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 _darwin_node_driver_h_
00026 #define _darwin_node_driver_h_
00027
00028 #include <iri_base_driver/iri_base_driver.h>
00029 #include <iri_darwin_robot/DarwinRobotConfig.h>
00030
00031
00032 #include "darwin_robot.h"
00033 #include "darwin_exceptions.h"
00034
00054 class DarwinRobotDriver : public iri_base_driver::IriBaseDriver
00055 {
00056 private:
00057
00058 CDarwin *robot;
00059
00060 std::string CM730_device;
00061
00062 std::string action_file;
00063
00064 std::string config_file;
00065 public:
00072 typedef iri_darwin_robot::DarwinRobotConfig Config;
00073
00080 Config config_;
00081
00090 DarwinRobotDriver(void);
00091
00102 bool openDriver(void);
00103
00114 bool closeDriver(void);
00115
00126 bool startDriver(void);
00127
00138 bool stopDriver(void);
00139
00151 void config_update(Config& new_cfg, uint32_t level=0);
00152
00153
00154
00155 std::vector<double> get_current_angles(void);
00156
00157 void start_walking(double x_dist, double y_dist, double turn_angle);
00158 void tune_walking(double x_dist,double y_dist, double turn_angle);
00159 void set_walking_param(motion_params param, double value);
00160 double get_walking_param(motion_params param);
00161 void stop_walking(void);
00162 bool is_walking(void);
00163
00164 void start_action(unsigned int action_index);
00165 void start_action(std::string &action_name);
00166 void stop_action(void);
00167 void break_action(void);
00168 bool action_is_running(void);
00169
00170 void get_head_position(double *pan, double *tilt);
00171 void set_head_position(double pan, double tilt);
00172
00173 void get_gyroscope(double *x,double *y, double *z);
00174 void get_accelerometer(double *x, double *y, double *z);
00175 void get_analog_channel(analogs id,double *value);
00176
00177 std::string move_joints(std::vector<int> &servos,std::vector<double> &angles,std::vector<double> &speeds, std::vector<double> &accels, const std::string &target_id=std::string(""));
00178 bool joints_are_moving(std::string &target_id);
00179 void stop_joints(std::string &target_id);
00180
00181 void start_head_tracking(void);
00182 void stop_head_tracking(void);
00183 void set_tracking_pid(int t, TPID *pan_pid, TPID *tilt_pid);
00184 void get_tracking_pid(int *t, TPID *pan_pid, TPID *tilt_pid);
00185 void set_tracking_target(double pan, double tilt);
00186 void get_tracking_target(double *pan, double *tilt);
00193 ~DarwinRobotDriver(void);
00194 };
00195
00196 #endif