Skip to content

Commit

Permalink
Merge pull request #597 from k-okada/fix_iob2
Browse files Browse the repository at this point in the history
fix iob for downstream packages
  • Loading branch information
fkanehiro committed Apr 22, 2015
2 parents 54ff35f + c07ca55 commit 3dff336
Show file tree
Hide file tree
Showing 6 changed files with 13 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 2 additions & 0 deletions lib/io/iob.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
2 changes: 2 additions & 0 deletions lib/io/iob.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
4 changes: 4 additions & 0 deletions rtc/RobotHardware/RobotHardwareService_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 2 additions & 0 deletions rtc/RobotHardware/robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
2 changes: 2 additions & 0 deletions rtc/RobotHardware/robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -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]
Expand Down

0 comments on commit 3dff336

Please sign in to comment.