From c07ca55594a6cc44a001046c66fbc449c2fdcde9 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Wed, 22 Apr 2015 20:03:09 +0900 Subject: [PATCH] [lib/io/iob{cpp,h},rtc/RobotHardware/{robot.cpp,robot.h,RobotHardwareService_impl.cpp,CMakeList.txt] add ROBOT_IOB_VERSION for backword compatibility --- CMakeLists.txt | 1 + lib/io/iob.cpp | 2 ++ lib/io/iob.h | 2 ++ rtc/RobotHardware/RobotHardwareService_impl.cpp | 4 ++++ rtc/RobotHardware/robot.cpp | 2 ++ rtc/RobotHardware/robot.h | 2 ++ 6 files changed, 13 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 460e15651fc..35951dfc4a7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -152,6 +152,7 @@ install(FILES DESTINATION lib/pkgconfig) add_definitions(-DHRPSYS_PACKAGE_VERSION=\"\\"${CPACK_PACKAGE_VERSION_MAJOR}.${CPACK_PACKAGE_VERSION_MINOR}.${CPACK_PACKAGE_VERSION_PATCH}\\"\") +add_definitions(-DROBOT_IOB_VERSION=2) if(COMPILE_JAVA_STUFF) add_subdirectory(jython) diff --git a/lib/io/iob.cpp b/lib/io/iob.cpp index e284a8d9361..c9614c2de44 100644 --- a/lib/io/iob.cpp +++ b/lib/io/iob.cpp @@ -569,11 +569,13 @@ int read_power(double *voltage, double *current) return TRUE; } +#if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 int read_battery(double *battery) { *battery = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*0.5+50; return TRUE; } +#endif int read_driver_temperature(int id, unsigned char *v) { diff --git a/lib/io/iob.h b/lib/io/iob.h index 5f49360e0c8..9d2f3c2b68d 100644 --- a/lib/io/iob.h +++ b/lib/io/iob.h @@ -577,6 +577,7 @@ extern "C"{ int read_power(double *v, double *a); //@} +#if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 //@{ /** * @brief read status of battery source this is new API since 315.4.0 @@ -585,6 +586,7 @@ extern "C"{ */ int read_battery(double *b) /* {} */; // if you are compiling against old libiob.so, please uncomment to dummy define this function. //@} +#endif /** * @name thermometer diff --git a/rtc/RobotHardware/RobotHardwareService_impl.cpp b/rtc/RobotHardware/RobotHardwareService_impl.cpp index 44f482a6993..8d9aa77dbbd 100644 --- a/rtc/RobotHardware/RobotHardwareService_impl.cpp +++ b/rtc/RobotHardware/RobotHardwareService_impl.cpp @@ -81,7 +81,11 @@ void RobotHardwareService_impl::getStatus2(OpenHRP::RobotHardwareService::RobotS GetStatus +#if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 m_robot->readPowerStatus(rs->voltage, rs->current, rs->battery); +#else + m_robot->readPowerStatus(rs->voltage, rs->current); +#endif } CORBA::Boolean RobotHardwareService_impl::power(const char* jname, OpenHRP::RobotHardwareService::SwitchStatus ss) diff --git a/rtc/RobotHardware/robot.cpp b/rtc/RobotHardware/robot.cpp index 19bde795160..364c54847c4 100644 --- a/rtc/RobotHardware/robot.cpp +++ b/rtc/RobotHardware/robot.cpp @@ -464,11 +464,13 @@ void robot::readPowerStatus(double &o_voltage, double &o_current) read_power(&o_voltage, &o_current); } +#if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 void robot::readPowerStatus(double &o_voltage, double &o_current, double &o_battery) { read_power(&o_voltage, &o_current); read_battery(&o_battery); } +#endif int robot::readCalibState(int i) { diff --git a/rtc/RobotHardware/robot.h b/rtc/RobotHardware/robot.h index 1141b015fe8..f06963a7d2b 100644 --- a/rtc/RobotHardware/robot.h +++ b/rtc/RobotHardware/robot.h @@ -130,7 +130,9 @@ class robot : public hrp::Body \param o_battery remaining battery level ( new feature on 315.4.0) */ void readPowerStatus(double &o_voltage, double &o_current); +#if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 void readPowerStatus(double &o_voltage, double &o_current, double &o_battery); +#endif /** \brief read array of all joint angles[rad]