types.h
Go to the documentation of this file.
00001 /**************************************************************************************************
00002  Software License Agreement (BSD License)
00003 
00004  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
00005  All rights reserved.
00006 
00007  Redistribution and use in source and binary forms, with or without modification, are permitted
00008  provided that the following conditions are met:
00009 
00010   *Redistributions of source code must retain the above copyright notice, this list of
00011    conditions and the following disclaimer.
00012   *Redistributions in binary form must reproduce the above copyright notice, this list of
00013    conditions and the following disclaimer in the documentation and/or other materials provided
00014    with the distribution.
00015   *Neither the name of the University of Aveiro nor the names of its contributors may be used to
00016    endorse or promote products derived from this software without specific prior written permission.
00017  
00018  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
00019  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
00020  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
00021  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00022  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00023  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
00024  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
00025  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 ***************************************************************************************************/
00034 #ifndef _TYPES_H_
00035 #define _TYPES_H_
00036 
00037 #include <hitec5980sg/hitec5980sg.h>
00038 
00039 #include <iostream>
00040 #include <pthread.h>
00041 #include <gtk/gtk.h>
00042 #include <glib.h>
00043 
00044 #include <boost/lexical_cast.hpp>
00045 #include <boost/format.hpp>
00046 
00047 #include <HD/hd.h>
00048 #include <HDU/hduVector.h>
00049 #include <HDU/hduError.h>
00050 #include <HDU/hduMatrix.h>
00051 #include <HDU/hduPlane.h>
00052 #include <HL/hl.h>
00053 
00054 #include <phua_haptic/humanoid_functions.h>
00055 
00056 #include <ros/ros.h>
00057 #include "tf/transform_datatypes.h"
00058 #include <tf/transform_broadcaster.h>
00059 #include <tf/transform_listener.h>
00060 
00064 typedef struct{
00065   //robot joints
00066   double HeadTilt;
00067   double RightShoulderFlexion;
00068   double RightShoulderAbduction;
00069   double RightElbowFlexion;
00070   double LeftShoulderFlexion;
00071   double LeftShoulderAbduction;
00072   double LeftElbowFlexion;
00073   double TorsoRotation;
00074   double TorsoFlexion;
00075   double TorsoLateralFlexion;
00076   double RightAnkleInversion;
00077   double RightAnkleFlexion;
00078   double RightKneeFlexion;
00079   double RightHipAbduction;
00080   double RightHipFlexion;
00081   double LeftAnkleInversion;
00082   double LeftAnkleFlexion;
00083   double LeftKneeFlexion;
00084   double LeftHipAbduction;
00085   double LeftHipFlexion;
00086   // -> arm coordinates & RPY | shoulder referencial
00087   double X_arm_end_left;
00088   double Y_arm_end_left;
00089   double Z_arm_end_left;
00090   double ROLL_arm_end_left;
00091   double PITCH_arm_end_left;
00092   double YAW_arm_end_left;
00093   double X_arm_end_right;
00094   double Y_arm_end_right;
00095   double Z_arm_end_right;
00096   double ROLL_arm_end_right;
00097   double PITCH_arm_end_right;
00098   double YAW_arm_end_right;
00099   // -> detached legs coordinates & RPY | foot referencial
00100   double detached_leg_pos_left[3];
00101   double detached_leg_rpy_left[3];
00102   double detached_leg_pos_right[3];
00103   double detached_leg_rpy_right[3];
00104   //Centers of gravity
00105   Eigen::Vector3d COG_detached_leg_left;
00106   Eigen::Vector3d COG_detached_leg_right;
00107 }RobotKinData;
00108 
00112 typedef struct{
00113   // robot joint space labels
00114   GtkWidget *joints_left_side;
00115   GtkWidget *joints_right_side;
00116   GtkWidget *x_label_left;
00117   GtkWidget *y_label_left;
00118   GtkWidget *z_label_left;
00119   GtkWidget *roll_label_left;
00120   GtkWidget *pitch_label_left;
00121   GtkWidget *yaw_label_left;
00122   GtkWidget *x_label_right;
00123   GtkWidget *y_label_right;
00124   GtkWidget *z_label_right;
00125   GtkWidget *roll_label_right;
00126   GtkWidget *pitch_label_right;
00127   GtkWidget *yaw_label_right;
00128   GtkWidget *head_tilt_label;
00129   GtkWidget *right_arm_label;
00130   GtkWidget *left_arm_label;
00131   GtkWidget *torso_label;
00132   GtkWidget *right_leg_label;
00133   GtkWidget *left_leg_label;
00134   // haptic device labels
00135   GtkWidget *phantom_x_label;
00136   GtkWidget *phantom_y_label;
00137   GtkWidget *phantom_z_label;
00138   GtkWidget *phantom_pen_tip_x_label;
00139   GtkWidget *phantom_pen_tip_y_label;
00140   GtkWidget *phantom_pen_tip_z_label;
00141   GtkWidget *phantom_speed_label;
00142   GtkWidget *phantom_jnt1_label;
00143   GtkWidget *phantom_jnt2_label;
00144   GtkWidget *phantom_jnt3_label;
00145   GtkWidget *phantom_gbl1_label;
00146   GtkWidget *phantom_gbl2_label;
00147   GtkWidget *phantom_gbl3_label;
00148   // speed control progress bars
00149   GtkWidget *auto_speed_arm_theta1_bar;
00150   GtkWidget *auto_speed_arm_theta2_bar;
00151   GtkWidget *auto_speed_arm_theta3_bar;
00152   //haptic loop button
00153   GtkWidget *start_loop_button;
00154   //kinematic model combobox
00155   GtkWidget *kin_model_combobox;
00156   // haptic workspace interface label
00157   GtkWidget *workspace_zone_label;
00158   // haptic drawing demo
00159   GtkWidget *drawing_demo_label;
00160   GtkWidget *drawing_demo_plane_label;
00161   // leg balancing demo
00162   GtkWidget *leg_balancing_demo_label;
00163   //user path demo
00164   GtkWidget *user_path_label;
00165   GtkWidget *user_path_run_button;
00166   // force feedback progress bars
00167   GtkWidget *pos_x_force_bar;
00168   GtkWidget *neg_x_force_bar;
00169   GtkWidget *pos_y_force_bar;
00170   GtkWidget *neg_y_force_bar;
00171   GtkWidget *pos_z_force_bar;
00172   GtkWidget *neg_z_force_bar;
00173   // force magnitude
00174   GtkWidget *force_magnitude_label;
00175   // motor temperature labels
00176   GtkWidget *motor_1_temp;
00177   GtkWidget *motor_2_temp;
00178   GtkWidget *motor_3_temp;
00179   // status bar
00180   GtkWidget *status_bar;
00181   //demos
00182   GtkWidget *demo1_checkbox;
00183   GtkWidget *demo2_checkbox;
00184   GtkWidget *demo3_checkbox;
00185   GtkWidget *demo4_checkbox;
00186   //stop/go
00187   GtkWidget *stop_button;
00188   GtkWidget *go_button;
00189 }WidgetCollection;
00190 
00194 typedef struct 
00195 {
00196   HHLRC hHLRC; //context for haptic feedbac/control
00197   HHD hHD; //current device (PHANToM)
00198   HDboolean m_button1State;
00199   HDboolean m_button2State;
00200   bool m_button1Clicked;
00201   bool m_button2Clicked;
00202   hduVector3Dd m_devicePosition; //mm
00203   hduVector3Dd jointAngles; //rad
00204   hduVector3Dd gimbalAngles; //rad
00205   hduVector3Dd average_speed; //mm/s
00206   HDErrorInfo m_error;
00207   bool phantom_on;
00208   HDdouble max_stiffness;
00209   HDdouble max_damping;
00210   HDdouble max_force; //Newton
00211   HDdouble max_continuous_force; //Newton
00212   HDdouble motor_temperature[3];
00213   bool need_update;
00214   hduMatrix end_effector_transform;
00215   hduVector3Dd m_PenTipPosition;
00216   tf::Transform world_to_phantom;
00217   tf::Transform phantom_to_base_point;
00218   tf::Transform base_point_to_pen_tip;
00219 } DeviceData;
00220 
00224 typedef struct 
00225 {
00226   bool exit_status;
00227   double coordinate_resolution;
00228   double automatic_speed_control_freq;
00229   int kinematic_model;
00230   bool manual_speed_control;
00231   short unsigned int manual_speed;
00232   bool automatic_speed_control;
00233   double arm_auto_angular_speed[3];
00234   short unsigned int arm_auto_speed[3];
00235   double pos_coord_scale;
00236   unsigned int selected_notebook_page;
00237   double cntrl_pos_back_front;
00238   short unsigned int robot_home_position_base_speed;
00239   unsigned int control_rate;
00240   double graphics_refresh_rate;
00241   unsigned int haptics_rate;
00242 } ParameterSet;
00243 
00247 typedef struct 
00248 {
00249   hduVector3Dd arm_main_spheresPosition;
00250   hduVector3Dd arm_back_spherePosition;
00251   double arm_main_sphere_max_Radius;
00252   double arm_main_sphere_min_Radius;
00253   double arm_back_sphereRadius;
00254   hduVector3Dd leg_main_spheresPosition;
00255   hduVector3Dd leg_back_spherePosition;
00256   hduVector3Dd leg_front_spherePosition;
00257   double leg_main_sphere_max_Radius;
00258   double leg_main_sphere_min_Radius;
00259   double leg_back_sphereRadius;
00260   hduVector3Dd applied_force;
00261   short unsigned int force_threshold;
00262   short unsigned int chosen_demo;
00263   hduVector3Dd demo_2_point_1;
00264   hduVector3Dd demo_2_point_2;
00265   hduVector3Dd demo_2_point_3;
00266   hduPlaned demo_2_Plane;
00267   double demo2_distance_to_plane;
00268   bool demo_user_path_point_storing;
00269   bool demo_user_path_is_run_once;
00270   bool demo_user_path_run_start;
00271   std::vector<double> user_path_X_pnts;
00272   std::vector<double> user_path_Y_pnts;
00273   std::vector<double> user_path_Z_pnts;
00274 } HapticsData;
00275 
00279 typedef struct
00280 {
00281   hitec_5980SG *servo;
00282   RobotKinData robot_kin_data;
00283   pthread_mutex_t mutex_gtk;
00284   WidgetCollection updt_labels;
00285   DeviceData phantom_data;
00286   ParameterSet parameters;
00287   bool haptic_loop_start;
00288   bool update_labels;
00289   HapticsData haptics_data;
00290   humanoid *humanoid_f;
00291 }shared_vars_t;
00292 
00293 #endif
00294 


phua_haptic
Author(s): Pedro Cruz
autogenerated on Thu Nov 20 2014 11:35:52