#include <ros/ros.h>#include <ros/callback_queue.h>#include <blackboard/remote.h>#include <blackboard/interface_listener.h>#include <interfaces/ZoneInterface.h>#include <interfaces/Position3DInterface.h>#include <interfaces/TagVisionInterface.h>#include <interfaces/RobotinoLightInterface.h>#include <interfaces/NavGraphWithMPSGeneratorInterface.h>#include <utils/time/time.h>#include <rcll_fawkes_sim_msgs/ExplorationZoneInfo.h>#include <rcll_fawkes_sim_msgs/MPSMarkerArray.h>#include <rcll_fawkes_sim_msgs/MPSLightState.h>#include <rcll_fawkes_sim_msgs/NavgraphWithMPSGenerate.h>#include <geometry_msgs/PoseWithCovarianceStamped.h>#include <memory>
Go to the source code of this file.
Classes | |
| class | RcllFawkesSimNode |
Defines | |
| #define | GET_PRIV_PARAM(P) |
Functions | |
| int | fawkes_to_ros_light_state (const fawkes::RobotinoLightInterface::LightState &state) |
| int | main (int argc, char **argv) |
| fawkes::NavGraphWithMPSGeneratorInterface::Side | ros_to_fawkes_mps_side (int side) |
| #define GET_PRIV_PARAM | ( | P | ) |
{ \
if (! ros::param::get("~" #P, cfg_ ## P ## _)) { \
ROS_ERROR("%s: Failed to retrieve parameter " #P ", aborting", ros::this_node::getName().c_str()); \
exit(-1); \
} \
}
Definition at line 43 of file rcll_fawkes_sim_node.cpp.
| int fawkes_to_ros_light_state | ( | const fawkes::RobotinoLightInterface::LightState & | state | ) |
Definition at line 52 of file rcll_fawkes_sim_node.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 349 of file rcll_fawkes_sim_node.cpp.
| fawkes::NavGraphWithMPSGeneratorInterface::Side ros_to_fawkes_mps_side | ( | int | side | ) |
Definition at line 66 of file rcll_fawkes_sim_node.cpp.