#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <std_msgs/String.h>
#include <std_msgs/Bool.h>
#include <geometry_msgs/PoseStamped.h>
#include <actionlib/client/simple_action_client.h>
#include <actionlib_msgs/GoalStatus.h>
#include <move_base_msgs/MoveBaseAction.h>
#include <stdio.h>
#include <string>
#include <sstream>
#include "video_player/PlayVideoSrv.h"
Go to the source code of this file.
Enumerations | |
enum | state { START, RETURN_START, WAIT_PERSON, APPROACH_PERSON, ASK_PERSON, WAIT_BUTTON_TOUR, APPROACH_PRESENTATION, PRESENT, ASK_REPETITION, WAIT_BUTTON_REPETITION, TALK_BYE } |
Functions | |
void | buttonCb (std_msgs::Bool msg) |
void | createPoseFromParams (std::string param_name, geometry_msgs::PoseStamped *pose) |
int | main (int argc, char **argv) |
Variables | |
int | current_goal = 0 |
ros::Time | last_button_msg_time |
bool | last_button_state = false |
enum state |
START | |
RETURN_START | |
WAIT_PERSON | |
APPROACH_PERSON | |
ASK_PERSON | |
WAIT_BUTTON_TOUR | |
APPROACH_PRESENTATION | |
PRESENT | |
ASK_REPETITION | |
WAIT_BUTTON_REPETITION | |
TALK_BYE |
Definition at line 39 of file state_machine.cpp.
void buttonCb | ( | std_msgs::Bool | msg | ) |
Callback function that received a boolean ROS message an stores the content and the receive time in global variables as the bool message does not contain a header structure.
INPUT: std_msgs::Bool msg: message
OUTPUT: none
void createPoseFromParams | ( | std::string | param_name, |
geometry_msgs::PoseStamped * | pose | ||
) |
Function that extracts a PoseStamped representation from the parameter group param_name of the goals namespace and stores it in the provided.
INPUT: std::string param_name: name of the PoseStamped parameter geometry_msgs::PoseStamped* pose: reference to the pose that to be changed OUTPUT: none
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 43 of file state_machine.cpp.
int current_goal = 0 |
Definition at line 31 of file state_machine.cpp.
Node that uses the WheeledRobin robot to perform a guided tour with multiple stops. It provides interfaces to nodes for navigation, speech synthesis, physical user interfaces and displaying graphics and uses a state machine to manage the workflow.
JKU Linz Institute for Robotics Alexander Reiter, Armin Steinhauser December 2013
Definition at line 30 of file state_machine.cpp.
bool last_button_state = false |
Definition at line 36 of file state_machine.cpp.