Defines | Enumerations | Functions | Variables
iob.cpp File Reference
#include <unistd.h>
#include <iostream>
#include <string>
#include <cstdlib>
#include <cstring>
#include <vector>
#include "io/iob.h"
#include <ros/ros.h>
#include <boost/algorithm/string.hpp>
#include <osrf_msgs/JointCommands.h>
#include <sensor_msgs/JointState.h>
#include <sensor_msgs/Imu.h>
#include <atlas_msgs/AtlasState.h>
#include <atlas_msgs/AtlasCommand.h>
#include <hrpUtil/Eigen3d.h>
Include dependency graph for iob.cpp:

Go to the source code of this file.

Defines

#define CHECK_ACCELEROMETER_ID(id)   if ((id) < 0 || (id) >= number_of_accelerometers()) return E_ID
#define CHECK_ATTITUDE_SENSOR_ID(id)   if ((id) < 0 || (id) >= number_of_attitude_sensors()) return E_ID
#define CHECK_FORCE_SENSOR_ID(id)   if ((id) < 0 || (id) >= number_of_force_sensors()) return E_ID
#define CHECK_GYRO_SENSOR_ID(id)   if ((id) < 0 || (id) >= number_of_gyro_sensors()) return E_ID
#define CHECK_JOINT_ID(id)   if ((id) < 0 || (id) >= number_of_joints()) return E_ID
#define JOINT_ID_MODEL2REAL(id)   get_joint_id_model2real(id)
#define JOINT_ID_REAL2MODEL(id)   get_joint_id_real2model(id)
#define NUM_OF_REAL_JOINT   get_num_of_real_joint()

Enumerations

enum  AtlasName { ATLAS_V0, ATLAS_V3, UNKNOWN }

Functions

int close_iob (void)
static int get_joint_id_model2real (int id)
static int get_joint_id_real2model (int id)
static int get_num_of_real_joint ()
long get_signal_period ()
int initializeJointAngle (const char *name, const char *option)
int joint_calibration (int id, double angle)
int length_digital_input (void)
int length_digital_output (void)
size_t length_of_extra_servo_state (int id)
int lock_iob ()
int number_of_accelerometers ()
int number_of_attitude_sensors ()
int number_of_force_sensors ()
int number_of_gyro_sensors ()
int number_of_joints ()
int number_of_substeps ()
int open_iob (void)
int read_accelerometer (int id, double *accels)
int read_accelerometer_offset (int id, double *offset)
int read_actual_angle (int id, double *angle)
int read_actual_angles (double *angles)
int read_actual_torques (double *torques)
int read_actual_velocities (double *vels)
int read_actual_velocity (int id, double *vel)
int read_angle_offset (int id, double *angle)
int read_attitude_sensor (int id, double *att)
int read_calib_state (int id, int *s)
int read_command_angle (int id, double *angle)
int read_command_angles (double *angles)
int read_command_torque (int id, double *torque)
int read_command_torques (double *torques)
int read_command_velocities (double *vels)
int read_command_velocity (int id, double *vel)
int read_control_mode (int id, joint_control_mode *s)
int read_current (int id, double *mcurrent)
int read_current_limit (int id, double *v)
int read_currents (double *currents)
int read_dgain (int id, double *gain)
int read_digital_input (char *dinput)
int read_digital_output (char *doutput)
int read_driver_temperature (int id, unsigned char *v)
int read_encoder_pulse (int id, double *ec)
int read_extra_servo_state (int id, int *state)
int read_force_offset (int id, double *offsets)
int read_force_sensor (int id, double *forces)
int read_gauges (double *gauges)
int read_gear_ratio (int id, double *gr)
int read_gyro_sensor (int id, double *rates)
int read_gyro_sensor_offset (int id, double *offset)
unsigned long long read_iob_frame ()
int read_limit_angle (int id, double *angle)
int read_llimit_angle (int id, double *angle)
int read_lock_owner (pid_t *pid)
int read_pgain (int id, double *gain)
int read_power (double *voltage, double *current)
int read_power_command (int id, int *com)
int read_power_state (int id, int *s)
int read_servo_alarm (int id, int *a)
int read_servo_state (int id, int *s)
int read_temperature (int id, double *v)
int read_torque_const (int id, double *tc)
int read_torque_limit (int id, double *limit)
int read_touch_sensors (unsigned short *onoff)
int read_ulimit_angle (int id, double *angle)
int reset_body (void)
int set_number_of_accelerometers (int num)
int set_number_of_attitude_sensors (int num)
int set_number_of_force_sensors (int num)
int set_number_of_gyro_sensors (int num)
int set_number_of_joints (int num)
int set_signal_period (long period_ns)
static void setJointStates (const atlas_msgs::AtlasState::ConstPtr &_js)
void timespec_add_ns (timespec *ts, long ns)
double timespec_compare (timespec *ts1, timespec *ts2)
int unlock_iob ()
static void update_atlas_name ()
int wait_for_iob_signal ()
int write_accelerometer_offset (int id, double *offset)
int write_angle_offset (int id, double angle)
int write_attitude_sensor_offset (int id, double *offset)
int write_command_angle (int id, double angle)
int write_command_angles (const double *angles)
int write_command_torque (int id, double torque)
int write_command_torques (const double *torques)
int write_command_velocities (const double *vels)
int write_command_velocity (int id, double vel)
int write_control_mode (int id, joint_control_mode s)
int write_dgain (int id, double gain)
int write_digital_output (const char *doutput)
int write_digital_output_with_mask (const char *doutput, const char *mask)
int write_dio (unsigned short buf)
int write_force_offset (int id, double *offsets)
int write_gyro_sensor_offset (int id, double *offset)
int write_pgain (int id, double gain)
int write_power_command (int id, int com)
int write_servo (int id, int com)

Variables

static std::vector
< std::vector< double > > 
accel_offset
static std::vector
< std::vector< double > > 
accelerometers
static enum AtlasName atlas_name = UNKNOWN
static std::vector
< std::vector< double > > 
attitude_sensors
static std::vector< double > command
static std::vector
< std::vector< double > > 
force_offset
static std::vector
< std::vector< double > > 
forces
static int frame = 0
static long g_period_ns = 3000000
static timespec g_ts
static std::vector
< std::vector< double > > 
gyro_offset
static std::vector
< std::vector< double > > 
gyros
static int init_sub_flag = FALSE
static atlas_msgs::AtlasCommand initial_jointcommands
static bool isLocked = false
static int joint_id_real2model_atlas_v0 [] = {0, 1, 2, 9, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 3, 4, 5, 6, 7, 8, 21, 22, 23, 24, 25, 26}
static int joint_id_real2model_atlas_v3 [] = {0, 1, 2, 11, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 3, 4, 5, 6, 7, 8, 23, 24, 25, 26, 27, 28}
static atlas_msgs::AtlasCommand jointcommands
static atlas_msgs::AtlasState js
static ros::Time last_callback_time
static std::vector< int > power
static std::vector< double > prev_command
static ros::Publisher pub_joint_commands_
static ros::Time rg_ts
static ros::NodeHandlerosnode
static std::vector< int > servo
static ros::Subscriber sub_atlas_state

Define Documentation

#define CHECK_ACCELEROMETER_ID (   id)    if ((id) < 0 || (id) >= number_of_accelerometers()) return E_ID

Definition at line 47 of file iob.cpp.

#define CHECK_ATTITUDE_SENSOR_ID (   id)    if ((id) < 0 || (id) >= number_of_attitude_sensors()) return E_ID

Definition at line 49 of file iob.cpp.

#define CHECK_FORCE_SENSOR_ID (   id)    if ((id) < 0 || (id) >= number_of_force_sensors()) return E_ID

Definition at line 46 of file iob.cpp.

#define CHECK_GYRO_SENSOR_ID (   id)    if ((id) < 0 || (id) >= number_of_gyro_sensors()) return E_ID

Definition at line 48 of file iob.cpp.

#define CHECK_JOINT_ID (   id)    if ((id) < 0 || (id) >= number_of_joints()) return E_ID

Definition at line 45 of file iob.cpp.

Definition at line 209 of file iob.cpp.

Definition at line 208 of file iob.cpp.

Definition at line 210 of file iob.cpp.


Enumeration Type Documentation

enum AtlasName
Enumerator:
ATLAS_V0 
ATLAS_V3 
UNKNOWN 

Definition at line 216 of file iob.cpp.


Function Documentation

int close_iob ( void  )

Definition at line 981 of file iob.cpp.

static int get_joint_id_model2real ( int  id) [static]

Definition at line 263 of file iob.cpp.

static int get_joint_id_real2model ( int  id) [static]

Definition at line 234 of file iob.cpp.

static int get_num_of_real_joint ( ) [static]

Definition at line 248 of file iob.cpp.

Definition at line 1225 of file iob.cpp.

int initializeJointAngle ( const char *  name,
const char *  option 
)

Definition at line 1230 of file iob.cpp.

int joint_calibration ( int  id,
double  angle 
)

Definition at line 995 of file iob.cpp.

int length_digital_input ( void  )

Definition at line 1246 of file iob.cpp.

int length_digital_output ( void  )

Definition at line 1256 of file iob.cpp.

size_t length_of_extra_servo_state ( int  id)

Definition at line 1209 of file iob.cpp.

int lock_iob ( )

Definition at line 1061 of file iob.cpp.

Definition at line 326 of file iob.cpp.

Definition at line 331 of file iob.cpp.

Definition at line 316 of file iob.cpp.

Definition at line 321 of file iob.cpp.

Definition at line 311 of file iob.cpp.

Definition at line 1126 of file iob.cpp.

int open_iob ( void  )

Definition at line 807 of file iob.cpp.

int read_accelerometer ( int  id,
double *  accels 
)

Definition at line 699 of file iob.cpp.

int read_accelerometer_offset ( int  id,
double *  offset 
)

Definition at line 1016 of file iob.cpp.

int read_actual_angle ( int  id,
double *  angle 
)

Definition at line 453 of file iob.cpp.

int read_actual_angles ( double *  angles)

Definition at line 470 of file iob.cpp.

int read_actual_torques ( double *  torques)

Definition at line 478 of file iob.cpp.

int read_actual_velocities ( double *  vels)

Definition at line 768 of file iob.cpp.

int read_actual_velocity ( int  id,
double *  vel 
)

Definition at line 753 of file iob.cpp.

int read_angle_offset ( int  id,
double *  angle 
)

Definition at line 1084 of file iob.cpp.

int read_attitude_sensor ( int  id,
double *  att 
)

Definition at line 728 of file iob.cpp.

int read_calib_state ( int  id,
int *  s 
)

Definition at line 1053 of file iob.cpp.

int read_command_angle ( int  id,
double *  angle 
)

Definition at line 515 of file iob.cpp.

int read_command_angles ( double *  angles)

Definition at line 529 of file iob.cpp.

int read_command_torque ( int  id,
double *  torque 
)

Definition at line 495 of file iob.cpp.

int read_command_torques ( double *  torques)

Definition at line 505 of file iob.cpp.

int read_command_velocities ( double *  vels)

Definition at line 773 of file iob.cpp.

int read_command_velocity ( int  id,
double *  vel 
)

Definition at line 758 of file iob.cpp.

int read_control_mode ( int  id,
joint_control_mode *  s 
)

Definition at line 440 of file iob.cpp.

int read_current ( int  id,
double *  mcurrent 
)

Definition at line 733 of file iob.cpp.

int read_current_limit ( int  id,
double *  v 
)

Definition at line 738 of file iob.cpp.

int read_currents ( double *  currents)

Definition at line 743 of file iob.cpp.

int read_dgain ( int  id,
double *  gain 
)

Definition at line 617 of file iob.cpp.

int read_digital_input ( char *  dinput)

Definition at line 1236 of file iob.cpp.

int read_digital_output ( char *  doutput)

Definition at line 1261 of file iob.cpp.

int read_driver_temperature ( int  id,
unsigned char *  v 
)

Definition at line 1138 of file iob.cpp.

int read_encoder_pulse ( int  id,
double *  ec 
)

Definition at line 1102 of file iob.cpp.

int read_extra_servo_state ( int  id,
int *  state 
)

Definition at line 1214 of file iob.cpp.

int read_force_offset ( int  id,
double *  offsets 
)

Definition at line 1032 of file iob.cpp.

int read_force_sensor ( int  id,
double *  forces 
)

Definition at line 642 of file iob.cpp.

int read_gauges ( double *  gauges)

Definition at line 748 of file iob.cpp.

int read_gear_ratio ( int  id,
double *  gr 
)

Definition at line 1106 of file iob.cpp.

int read_gyro_sensor ( int  id,
double *  rates 
)

Definition at line 666 of file iob.cpp.

int read_gyro_sensor_offset ( int  id,
double *  offset 
)

Definition at line 1000 of file iob.cpp.

unsigned long long read_iob_frame ( )

Definition at line 1119 of file iob.cpp.

int read_limit_angle ( int  id,
double *  angle 
)

Definition at line 1079 of file iob.cpp.

int read_llimit_angle ( int  id,
double *  angle 
)

Definition at line 1098 of file iob.cpp.

int read_lock_owner ( pid_t pid)

Definition at line 1074 of file iob.cpp.

int read_pgain ( int  id,
double *  gain 
)

Definition at line 591 of file iob.cpp.

int read_power ( double *  voltage,
double *  current 
)

Definition at line 1131 of file iob.cpp.

int read_power_command ( int  id,
int *  com 
)

Definition at line 419 of file iob.cpp.

int read_power_state ( int  id,
int *  s 
)

Definition at line 405 of file iob.cpp.

int read_servo_alarm ( int  id,
int *  a 
)

Definition at line 433 of file iob.cpp.

int read_servo_state ( int  id,
int *  s 
)

Definition at line 426 of file iob.cpp.

int read_temperature ( int  id,
double *  v 
)

Definition at line 783 of file iob.cpp.

int read_torque_const ( int  id,
double *  tc 
)

Definition at line 1110 of file iob.cpp.

int read_torque_limit ( int  id,
double *  limit 
)

Definition at line 1114 of file iob.cpp.

int read_touch_sensors ( unsigned short *  onoff)

Definition at line 723 of file iob.cpp.

int read_ulimit_angle ( int  id,
double *  angle 
)

Definition at line 1094 of file iob.cpp.

int reset_body ( void  )

Definition at line 987 of file iob.cpp.

int set_number_of_accelerometers ( int  num)

Definition at line 378 of file iob.cpp.

Definition at line 393 of file iob.cpp.

int set_number_of_force_sensors ( int  num)

Definition at line 348 of file iob.cpp.

int set_number_of_gyro_sensors ( int  num)

Definition at line 363 of file iob.cpp.

int set_number_of_joints ( int  num)

Definition at line 336 of file iob.cpp.

int set_signal_period ( long  period_ns)

Definition at line 1219 of file iob.cpp.

static void setJointStates ( const atlas_msgs::AtlasState::ConstPtr &  _js) [static]

Definition at line 800 of file iob.cpp.

void timespec_add_ns ( timespec ts,
long  ns 
)

Definition at line 1144 of file iob.cpp.

double timespec_compare ( timespec ts1,
timespec ts2 
)

Definition at line 1153 of file iob.cpp.

int unlock_iob ( )

Definition at line 1068 of file iob.cpp.

static void update_atlas_name ( ) [static]

Definition at line 219 of file iob.cpp.

Definition at line 1160 of file iob.cpp.

int write_accelerometer_offset ( int  id,
double *  offset 
)

Definition at line 1024 of file iob.cpp.

int write_angle_offset ( int  id,
double  angle 
)

Definition at line 1089 of file iob.cpp.

int write_attitude_sensor_offset ( int  id,
double *  offset 
)

Definition at line 1048 of file iob.cpp.

int write_command_angle ( int  id,
double  angle 
)

Definition at line 522 of file iob.cpp.

int write_command_angles ( const double *  angles)

Definition at line 537 of file iob.cpp.

int write_command_torque ( int  id,
double  torque 
)

Definition at line 500 of file iob.cpp.

int write_command_torques ( const double *  torques)

Definition at line 510 of file iob.cpp.

int write_command_velocities ( const double *  vels)

Definition at line 778 of file iob.cpp.

int write_command_velocity ( int  id,
double  vel 
)

Definition at line 763 of file iob.cpp.

int write_control_mode ( int  id,
joint_control_mode  s 
)

Definition at line 447 of file iob.cpp.

int write_dgain ( int  id,
double  gain 
)

Definition at line 629 of file iob.cpp.

int write_digital_output ( const char *  doutput)

Definition at line 1241 of file iob.cpp.

int write_digital_output_with_mask ( const char *  doutput,
const char *  mask 
)

Definition at line 1251 of file iob.cpp.

int write_dio ( unsigned short  buf)

Definition at line 794 of file iob.cpp.

int write_force_offset ( int  id,
double *  offsets 
)

Definition at line 1040 of file iob.cpp.

int write_gyro_sensor_offset ( int  id,
double *  offset 
)

Definition at line 1008 of file iob.cpp.

int write_pgain ( int  id,
double  gain 
)

Definition at line 604 of file iob.cpp.

int write_power_command ( int  id,
int  com 
)

Definition at line 412 of file iob.cpp.

int write_servo ( int  id,
int  com 
)

Definition at line 788 of file iob.cpp.


Variable Documentation

std::vector<std::vector<double> > accel_offset [static]

Definition at line 35 of file iob.cpp.

Definition at line 31 of file iob.cpp.

enum AtlasName atlas_name = UNKNOWN [static]

Definition at line 217 of file iob.cpp.

Definition at line 32 of file iob.cpp.

std::vector<double> command [static]

Definition at line 27 of file iob.cpp.

std::vector<std::vector<double> > force_offset [static]

Definition at line 33 of file iob.cpp.

std::vector<std::vector<double> > forces [static]

Definition at line 29 of file iob.cpp.

int frame = 0 [static]

Definition at line 39 of file iob.cpp.

long g_period_ns = 3000000 [static]

Definition at line 41 of file iob.cpp.

timespec g_ts [static]

Definition at line 40 of file iob.cpp.

std::vector<std::vector<double> > gyro_offset [static]

Definition at line 34 of file iob.cpp.

std::vector<std::vector<double> > gyros [static]

Definition at line 30 of file iob.cpp.

int init_sub_flag = FALSE [static]

Definition at line 25 of file iob.cpp.

atlas_msgs::AtlasCommand initial_jointcommands [static]

Definition at line 22 of file iob.cpp.

bool isLocked = false [static]

Definition at line 38 of file iob.cpp.

int joint_id_real2model_atlas_v0[] = {0, 1, 2, 9, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 3, 4, 5, 6, 7, 8, 21, 22, 23, 24, 25, 26} [static]

Definition at line 212 of file iob.cpp.

int joint_id_real2model_atlas_v3[] = {0, 1, 2, 11, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 3, 4, 5, 6, 7, 8, 23, 24, 25, 26, 27, 28} [static]

Definition at line 214 of file iob.cpp.

atlas_msgs::AtlasCommand jointcommands [static]

Definition at line 21 of file iob.cpp.

atlas_msgs::AtlasState js [static]

Definition at line 24 of file iob.cpp.

Definition at line 43 of file iob.cpp.

std::vector<int> power [static]

Definition at line 36 of file iob.cpp.

std::vector<double> prev_command [static]

Definition at line 28 of file iob.cpp.

Definition at line 19 of file iob.cpp.

ros::Time rg_ts [static]

Definition at line 42 of file iob.cpp.

Definition at line 18 of file iob.cpp.

std::vector<int> servo [static]

Definition at line 37 of file iob.cpp.

Definition at line 20 of file iob.cpp.



hrpsys_gazebo_atlas
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 10:53:59