Defines | Typedefs | Functions | Variables
iob.cpp File Reference
#include <unistd.h>
#include <iostream>
#include <cstdlib>
#include <cstring>
#include <vector>
#include "io/iob.h"
#include <ros/ros.h>
#include <boost/algorithm/string.hpp>
#include <hrpsys_gazebo_msgs/JointCommand.h>
#include <hrpsys_gazebo_msgs/RobotState.h>
#include <hrpsys_gazebo_msgs/SyncCommand.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)   joint_id_model2real(id)
#define JOINT_ID_REAL2MODEL(id)   joint_real2model_vec[id]
#define NUM_OF_REAL_JOINT   (joint_real2model_vec.size())
#define USE_SERVO_ON   0

Typedefs

typedef
hrpsys_gazebo_msgs::JointCommand 
JointCommand
typedef
hrpsys_gazebo_msgs::RobotState 
RobotState

Functions

int close_iob (void)
long get_signal_period ()
int initializeJointAngle (const char *name, const char *option)
int joint_calibration (int id, double angle)
static int joint_id_model2real (int id)
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 RobotState::ConstPtr &_js)
static void tick_service_command ()
void timespec_add_ns (timespec *ts, long ns)
double timespec_compare (timespec *ts1, timespec *ts2)
int unlock_iob ()
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 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 unsigned long long frame = 0
static long g_period_ns = 1000000
static timespec g_ts
static std::vector
< std::vector< double > > 
gyro_offset
static std::vector
< std::vector< double > > 
gyros
static bool init_sub_flag = false
static JointCommand initial_jointcommand
static bool iob_synchronized
static bool isLocked = false
static std::map< int, int > joint_model2real_map
static std::vector< int > joint_real2model_vec
static JointCommand jointcommand
static RobotState js
static int num_of_substeps = 1
static long overwrite_g_period_ns = -1
static std::vector< int > power
static std::vector< double > prev_command
static ros::Publisher pub_joint_command
static ros::Time rg_ts
static ros::NodeHandlerosnode
static ros::ServiceClient serv_command
static std::vector< int > servo
static bool start_robothw = false
static ros::Subscriber sub_robot_state
static bool use_velocity_feedback = false

Define Documentation

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

Definition at line 56 of file iob.cpp.

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

Definition at line 58 of file iob.cpp.

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

Definition at line 55 of file iob.cpp.

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

Definition at line 57 of file iob.cpp.

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

Definition at line 54 of file iob.cpp.

Definition at line 61 of file iob.cpp.

Definition at line 60 of file iob.cpp.

Definition at line 62 of file iob.cpp.

#define USE_SERVO_ON   0

Definition at line 64 of file iob.cpp.


Typedef Documentation

Definition at line 17 of file iob.cpp.

Definition at line 18 of file iob.cpp.


Function Documentation

int close_iob ( void  )

Definition at line 929 of file iob.cpp.

Definition at line 1172 of file iob.cpp.

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

Definition at line 1177 of file iob.cpp.

int joint_calibration ( int  id,
double  angle 
)

Definition at line 943 of file iob.cpp.

static int joint_id_model2real ( int  id) [inline, static]

Definition at line 69 of file iob.cpp.

int length_digital_input ( void  )

Definition at line 1193 of file iob.cpp.

int length_digital_output ( void  )

Definition at line 1203 of file iob.cpp.

size_t length_of_extra_servo_state ( int  id)

Definition at line 1153 of file iob.cpp.

int lock_iob ( )

Definition at line 1009 of file iob.cpp.

Definition at line 145 of file iob.cpp.

Definition at line 150 of file iob.cpp.

Definition at line 135 of file iob.cpp.

Definition at line 140 of file iob.cpp.

Definition at line 130 of file iob.cpp.

Definition at line 1078 of file iob.cpp.

int open_iob ( void  )

Definition at line 647 of file iob.cpp.

int read_accelerometer ( int  id,
double *  accels 
)

Definition at line 532 of file iob.cpp.

int read_accelerometer_offset ( int  id,
double *  offset 
)

Definition at line 964 of file iob.cpp.

int read_actual_angle ( int  id,
double *  angle 
)

Definition at line 276 of file iob.cpp.

int read_actual_angles ( double *  angles)

Definition at line 292 of file iob.cpp.

int read_actual_torques ( double *  torques)

Definition at line 300 of file iob.cpp.

int read_actual_velocities ( double *  vels)

Definition at line 600 of file iob.cpp.

int read_actual_velocity ( int  id,
double *  vel 
)

Definition at line 582 of file iob.cpp.

int read_angle_offset ( int  id,
double *  angle 
)

Definition at line 1032 of file iob.cpp.

int read_attitude_sensor ( int  id,
double *  att 
)

Definition at line 557 of file iob.cpp.

int read_calib_state ( int  id,
int *  s 
)

Definition at line 1001 of file iob.cpp.

int read_command_angle ( int  id,
double *  angle 
)

Definition at line 335 of file iob.cpp.

int read_command_angles ( double *  angles)

Definition at line 349 of file iob.cpp.

int read_command_torque ( int  id,
double *  torque 
)

Definition at line 315 of file iob.cpp.

int read_command_torques ( double *  torques)

Definition at line 325 of file iob.cpp.

int read_command_velocities ( double *  vels)

Definition at line 606 of file iob.cpp.

int read_command_velocity ( int  id,
double *  vel 
)

Definition at line 588 of file iob.cpp.

int read_control_mode ( int  id,
joint_control_mode *  s 
)

Definition at line 263 of file iob.cpp.

int read_current ( int  id,
double *  mcurrent 
)

Definition at line 562 of file iob.cpp.

int read_current_limit ( int  id,
double *  v 
)

Definition at line 567 of file iob.cpp.

int read_currents ( double *  currents)

Definition at line 572 of file iob.cpp.

int read_dgain ( int  id,
double *  gain 
)

Definition at line 446 of file iob.cpp.

int read_digital_input ( char *  dinput)

Definition at line 1183 of file iob.cpp.

int read_digital_output ( char *  doutput)

Definition at line 1208 of file iob.cpp.

int read_driver_temperature ( int  id,
unsigned char *  v 
)

Definition at line 1094 of file iob.cpp.

int read_encoder_pulse ( int  id,
double *  ec 
)

Definition at line 1050 of file iob.cpp.

int read_extra_servo_state ( int  id,
int *  state 
)

Definition at line 1158 of file iob.cpp.

int read_force_offset ( int  id,
double *  offsets 
)

Definition at line 980 of file iob.cpp.

int read_force_sensor ( int  id,
double *  forces 
)

Definition at line 484 of file iob.cpp.

int read_gauges ( double *  gauges)

Definition at line 577 of file iob.cpp.

int read_gear_ratio ( int  id,
double *  gr 
)

Definition at line 1054 of file iob.cpp.

int read_gyro_sensor ( int  id,
double *  rates 
)

Definition at line 504 of file iob.cpp.

int read_gyro_sensor_offset ( int  id,
double *  offset 
)

Definition at line 948 of file iob.cpp.

unsigned long long read_iob_frame ( )

Definition at line 1067 of file iob.cpp.

int read_limit_angle ( int  id,
double *  angle 
)

Definition at line 1027 of file iob.cpp.

int read_llimit_angle ( int  id,
double *  angle 
)

Definition at line 1046 of file iob.cpp.

int read_lock_owner ( pid_t pid)

Definition at line 1022 of file iob.cpp.

int read_pgain ( int  id,
double *  gain 
)

Definition at line 409 of file iob.cpp.

int read_power ( double *  voltage,
double *  current 
)

Definition at line 1087 of file iob.cpp.

int read_power_command ( int  id,
int *  com 
)

Definition at line 242 of file iob.cpp.

int read_power_state ( int  id,
int *  s 
)

Definition at line 228 of file iob.cpp.

int read_servo_alarm ( int  id,
int *  a 
)

Definition at line 256 of file iob.cpp.

int read_servo_state ( int  id,
int *  s 
)

Definition at line 249 of file iob.cpp.

int read_temperature ( int  id,
double *  v 
)

Definition at line 618 of file iob.cpp.

int read_torque_const ( int  id,
double *  tc 
)

Definition at line 1058 of file iob.cpp.

int read_torque_limit ( int  id,
double *  limit 
)

Definition at line 1062 of file iob.cpp.

int read_touch_sensors ( unsigned short *  onoff)

Definition at line 552 of file iob.cpp.

int read_ulimit_angle ( int  id,
double *  angle 
)

Definition at line 1042 of file iob.cpp.

int reset_body ( void  )

Definition at line 935 of file iob.cpp.

int set_number_of_accelerometers ( int  num)

Definition at line 200 of file iob.cpp.

Definition at line 216 of file iob.cpp.

int set_number_of_force_sensors ( int  num)

Definition at line 168 of file iob.cpp.

int set_number_of_gyro_sensors ( int  num)

Definition at line 184 of file iob.cpp.

int set_number_of_joints ( int  num)

Definition at line 155 of file iob.cpp.

int set_signal_period ( long  period_ns)

Definition at line 1163 of file iob.cpp.

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

Definition at line 638 of file iob.cpp.

static void tick_service_command ( ) [inline, static]

Definition at line 80 of file iob.cpp.

void timespec_add_ns ( timespec ts,
long  ns 
)

Definition at line 1100 of file iob.cpp.

double timespec_compare ( timespec ts1,
timespec ts2 
)

Definition at line 1109 of file iob.cpp.

int unlock_iob ( )

Definition at line 1016 of file iob.cpp.

Definition at line 1116 of file iob.cpp.

int write_accelerometer_offset ( int  id,
double *  offset 
)

Definition at line 972 of file iob.cpp.

int write_angle_offset ( int  id,
double  angle 
)

Definition at line 1037 of file iob.cpp.

int write_attitude_sensor_offset ( int  id,
double *  offset 
)

Definition at line 996 of file iob.cpp.

int write_command_angle ( int  id,
double  angle 
)

Definition at line 342 of file iob.cpp.

int write_command_angles ( const double *  angles)

Definition at line 357 of file iob.cpp.

int write_command_torque ( int  id,
double  torque 
)

Definition at line 320 of file iob.cpp.

int write_command_torques ( const double *  torques)

Definition at line 330 of file iob.cpp.

int write_command_velocities ( const double *  vels)

Definition at line 612 of file iob.cpp.

int write_command_velocity ( int  id,
double  vel 
)

Definition at line 594 of file iob.cpp.

int write_control_mode ( int  id,
joint_control_mode  s 
)

Definition at line 270 of file iob.cpp.

int write_dgain ( int  id,
double  gain 
)

Definition at line 466 of file iob.cpp.

int write_digital_output ( const char *  doutput)

Definition at line 1188 of file iob.cpp.

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

Definition at line 1198 of file iob.cpp.

int write_dio ( unsigned short  buf)

Definition at line 632 of file iob.cpp.

int write_force_offset ( int  id,
double *  offsets 
)

Definition at line 988 of file iob.cpp.

int write_gyro_sensor_offset ( int  id,
double *  offset 
)

Definition at line 956 of file iob.cpp.

int write_pgain ( int  id,
double  gain 
)

Definition at line 429 of file iob.cpp.

int write_power_command ( int  id,
int  com 
)

Definition at line 235 of file iob.cpp.

int write_servo ( int  id,
int  com 
)

Definition at line 623 of file iob.cpp.


Variable Documentation

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

Definition at line 43 of file iob.cpp.

Definition at line 39 of file iob.cpp.

Definition at line 40 of file iob.cpp.

std::vector<double> command [static]

Definition at line 35 of file iob.cpp.

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

Definition at line 41 of file iob.cpp.

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

Definition at line 37 of file iob.cpp.

unsigned long long frame = 0 [static]

Definition at line 47 of file iob.cpp.

long g_period_ns = 1000000 [static]

Definition at line 49 of file iob.cpp.

timespec g_ts [static]

Definition at line 48 of file iob.cpp.

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

Definition at line 42 of file iob.cpp.

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

Definition at line 38 of file iob.cpp.

bool init_sub_flag = false [static]

Definition at line 33 of file iob.cpp.

Definition at line 30 of file iob.cpp.

bool iob_synchronized [static]

Definition at line 25 of file iob.cpp.

bool isLocked = false [static]

Definition at line 46 of file iob.cpp.

std::map<int, int> joint_model2real_map [static]

Definition at line 66 of file iob.cpp.

Definition at line 67 of file iob.cpp.

Definition at line 29 of file iob.cpp.

RobotState js [static]

Definition at line 32 of file iob.cpp.

int num_of_substeps = 1 [static]

Definition at line 52 of file iob.cpp.

long overwrite_g_period_ns = -1 [static]

Definition at line 50 of file iob.cpp.

std::vector<int> power [static]

Definition at line 44 of file iob.cpp.

std::vector<double> prev_command [static]

Definition at line 36 of file iob.cpp.

Definition at line 23 of file iob.cpp.

ros::Time rg_ts [static]

Definition at line 51 of file iob.cpp.

Definition at line 20 of file iob.cpp.

Definition at line 22 of file iob.cpp.

std::vector<int> servo [static]

Definition at line 45 of file iob.cpp.

bool start_robothw = false [static]

Definition at line 26 of file iob.cpp.

Definition at line 24 of file iob.cpp.

bool use_velocity_feedback = false [static]

Definition at line 27 of file iob.cpp.



hrpsys_gazebo_general
Author(s): Yohei Kakiuchi , Kei Okada
autogenerated on Wed Sep 16 2015 10:52:48