#include <open_controllers_interface.h>
Public Member Functions | |
void | cleanupPidFile () |
void | diagnosticLoop () |
void | finalize () |
virtual void | finalizeHW ()=0 |
bool | haltMotorsService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) |
void | initialize () |
OpenController () | |
void | parseArguments (int argc, char **argv) |
bool | publishTraceService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) |
virtual void | quitRequest () |
bool | resetMotorsService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) |
void | setAllowUnprogrammedP (bool val) |
bool | setDryRun (bool _dryrun) |
void | setRobotXMLFile (std::string val) |
void | setStatsPublishP (bool val) |
int | setupPidFile () |
void | start () |
void | startMain () |
virtual bool | updateJoints (struct timespec *)=0 |
void | Usage (std::string msg="") |
int | waitThreadJoin () |
virtual | ~OpenController () |
Static Public Member Functions | |
static bool | initRT () |
Protected Member Functions | |
virtual void | initializeHW ()=0 |
virtual void | initializeROS (ros::NodeHandle &node)=0 |
int | lock_fd (int fd) |
double | now () |
void | publishDiagnostics () |
double | publishJitter (double start) |
void | timespecInc (struct timespec &tick, int nsec) |
Protected Attributes | |
bool | allow_unprogrammed_p |
boost::shared_ptr < pr2_controller_manager::ControllerManager > | cm |
bool | dryrunp |
bool | g_halt_motors |
bool | g_halt_requested |
bool | g_publish_trace_requested |
bool | g_quit |
bool | g_reset_motors |
std::string | g_robot_desc |
Stat | g_stats |
ros::ServiceServer | halt_service |
pr2_hardware_interface::HardwareInterface * | hw |
bool | initialized_p |
double | min_acceptable_rt_loop_frequency |
bool | not_sleep_clock |
double | period |
std::string | piddir |
std::string | pidfile |
realtime_tools::RealtimePublisher < diagnostic_msgs::DiagnosticArray > * | publisher |
ros::ServiceServer | publishTrace_service |
ros::ServiceServer | reset_service |
std::string | robot_xml_file |
realtime_tools::RealtimePublisher < std_msgs::Float64 > * | rtpublisher |
bool | stats_publish_p |
Definition at line 53 of file open_controllers_interface.h.
Definition at line 58 of file open_controllers_interface.cpp.
Definition at line 62 of file open_controllers_interface.cpp.
Definition at line 664 of file open_controllers_interface.cpp.
Definition at line 565 of file open_controllers_interface.cpp.
Definition at line 542 of file open_controllers_interface.cpp.
virtual void OpenControllersInterface::OpenController::finalizeHW | ( | ) | [pure virtual] |
bool OpenControllersInterface::OpenController::haltMotorsService | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | resp | ||
) |
Definition at line 71 of file open_controllers_interface.cpp.
Definition at line 203 of file open_controllers_interface.cpp.
virtual void OpenControllersInterface::OpenController::initializeHW | ( | ) | [protected, pure virtual] |
virtual void OpenControllersInterface::OpenController::initializeROS | ( | ros::NodeHandle & | node | ) | [protected, pure virtual] |
bool OpenControllersInterface::OpenController::initRT | ( | ) | [static] |
Definition at line 686 of file open_controllers_interface.cpp.
int OpenControllersInterface::OpenController::lock_fd | ( | int | fd | ) | [protected] |
Definition at line 576 of file open_controllers_interface.cpp.
double OpenControllersInterface::OpenController::now | ( | ) | [protected] |
Definition at line 330 of file open_controllers_interface.cpp.
void OpenControllersInterface::OpenController::parseArguments | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 169 of file open_controllers_interface.cpp.
void OpenControllersInterface::OpenController::publishDiagnostics | ( | ) | [protected] |
Definition at line 91 of file open_controllers_interface.cpp.
double OpenControllersInterface::OpenController::publishJitter | ( | double | start | ) | [protected] |
Definition at line 345 of file open_controllers_interface.cpp.
bool OpenControllersInterface::OpenController::publishTraceService | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | resp | ||
) |
Definition at line 77 of file open_controllers_interface.cpp.
void OpenControllersInterface::OpenController::quitRequest | ( | ) | [virtual] |
Definition at line 682 of file open_controllers_interface.cpp.
bool OpenControllersInterface::OpenController::resetMotorsService | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | resp | ||
) |
Definition at line 65 of file open_controllers_interface.cpp.
void OpenControllersInterface::OpenController::setAllowUnprogrammedP | ( | bool | val | ) | [inline] |
Definition at line 62 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::setDryRun | ( | bool | _dryrun | ) | [inline] |
Definition at line 74 of file open_controllers_interface.h.
void OpenControllersInterface::OpenController::setRobotXMLFile | ( | std::string | val | ) | [inline] |
Definition at line 70 of file open_controllers_interface.h.
void OpenControllersInterface::OpenController::setStatsPublishP | ( | bool | val | ) | [inline] |
Definition at line 66 of file open_controllers_interface.h.
Definition at line 589 of file open_controllers_interface.cpp.
Definition at line 87 of file open_controllers_interface.cpp.
Definition at line 362 of file open_controllers_interface.cpp.
void OpenControllersInterface::OpenController::timespecInc | ( | struct timespec & | tick, |
int | nsec | ||
) | [protected] |
Definition at line 336 of file open_controllers_interface.cpp.
virtual bool OpenControllersInterface::OpenController::updateJoints | ( | struct timespec * | ) | [pure virtual] |
void OpenControllersInterface::OpenController::Usage | ( | std::string | msg = "" | ) |
Definition at line 669 of file open_controllers_interface.cpp.
int OpenControllersInterface::OpenController::waitThreadJoin | ( | ) | [inline] |
Definition at line 81 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::allow_unprogrammed_p [protected] |
Definition at line 120 of file open_controllers_interface.h.
boost::shared_ptr<pr2_controller_manager::ControllerManager> OpenControllersInterface::OpenController::cm [protected] |
Definition at line 133 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::dryrunp [protected] |
Definition at line 118 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::g_halt_motors [protected] |
Definition at line 126 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::g_halt_requested [protected] |
Definition at line 125 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::g_publish_trace_requested [protected] |
Definition at line 127 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::g_quit [protected] |
Definition at line 124 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::g_reset_motors [protected] |
Definition at line 123 of file open_controllers_interface.h.
std::string OpenControllersInterface::OpenController::g_robot_desc [protected] |
Definition at line 131 of file open_controllers_interface.h.
Definition at line 136 of file open_controllers_interface.h.
Definition at line 139 of file open_controllers_interface.h.
Definition at line 132 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::initialized_p [protected] |
Definition at line 122 of file open_controllers_interface.h.
double OpenControllersInterface::OpenController::min_acceptable_rt_loop_frequency [protected] |
Definition at line 129 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::not_sleep_clock [protected] |
Definition at line 119 of file open_controllers_interface.h.
double OpenControllersInterface::OpenController::period [protected] |
Definition at line 130 of file open_controllers_interface.h.
std::string OpenControllersInterface::OpenController::piddir [protected] |
Definition at line 116 of file open_controllers_interface.h.
std::string OpenControllersInterface::OpenController::pidfile [protected] |
Definition at line 117 of file open_controllers_interface.h.
realtime_tools::RealtimePublisher<diagnostic_msgs::DiagnosticArray>* OpenControllersInterface::OpenController::publisher [protected] |
Definition at line 135 of file open_controllers_interface.h.
Definition at line 140 of file open_controllers_interface.h.
Definition at line 138 of file open_controllers_interface.h.
std::string OpenControllersInterface::OpenController::robot_xml_file [protected] |
Definition at line 128 of file open_controllers_interface.h.
realtime_tools::RealtimePublisher<std_msgs::Float64>* OpenControllersInterface::OpenController::rtpublisher [protected] |
Definition at line 134 of file open_controllers_interface.h.
bool OpenControllersInterface::OpenController::stats_publish_p [protected] |
Definition at line 121 of file open_controllers_interface.h.