Public Member Functions | Private Member Functions | Private Attributes
turtlebot_panorama::PanoApp Class Reference

#include <panorama.h>

List of all members.

Public Member Functions

void init ()
void log (std::string msg)
 PanoApp ()
void spin ()
 ~PanoApp ()

Private Member Functions

void activeCb ()
void doneCb (const actionlib::SimpleClientGoalState &state, const pano_ros::PanoCaptureResultConstPtr &result)
void feedbackCb (const pano_ros::PanoCaptureFeedbackConstPtr &feedback)
bool hasReachedAngle ()
void odomCb (const nav_msgs::OdometryConstPtr &msg)
void rotate ()
void snap ()
void startPanoAction ()
void stitchedImageCb (const sensor_msgs::ImageConstPtr &msg)
void stopPanoAction ()
void stopPanoCb (const std_msgs::EmptyConstPtr &msg)
void takePanoCb (const std_msgs::EmptyConstPtr &msg)
bool takePanoServiceCb (turtlebot_msgs::TakePanorama::Request &request, turtlebot_msgs::TakePanorama::Response &response)

Private Attributes

double ang_vel_cur
double angle
geometry_msgs::Twist cmd_vel
bool continuous
int default_mode
double default_pano_angle
double default_rotation_velocity
double default_snap_interval
std_msgs::Empty empty_msg
double given_angle
bool go_active
bool is_active
double last_angle
ros::NodeHandle nh
actionlib::SimpleActionClient
< pano_ros::PanoCaptureAction > * 
pano_ros_client
std::map< std::string,
std::string
params
ros::NodeHandle priv_nh
ros::Publisher pub_action_snap
ros::Publisher pub_action_stop
ros::Publisher pub_cmd_vel
ros::Publisher pub_log
image_transport::Publisher pub_stitched
double snap_interval
ros::ServiceServer srv_start_pano
ros::Subscriber sub_odom
ros::Subscriber sub_start_pano
image_transport::Subscriber sub_stitched
ros::Subscriber sub_stop_pano
geometry_msgs::Twist zero_cmd_vel

Detailed Description

The PanoApp utilises pano_ros for creating panorama pictures.

Definition at line 68 of file panorama.h.


Constructor & Destructor Documentation

Definition at line 49 of file panorama.cpp.

Definition at line 64 of file panorama.cpp.


Member Function Documentation

Triggered when the pano_ros action goal went active

Definition at line 365 of file panorama.cpp.

void turtlebot_panorama::PanoApp::doneCb ( const actionlib::SimpleClientGoalState state,
const pano_ros::PanoCaptureResultConstPtr &  result 
) [private]

Triggered when the pano_ros action goal has finished

Parameters:
stateSNAPANDROTATE
result

Definition at line 358 of file panorama.cpp.

void turtlebot_panorama::PanoApp::feedbackCb ( const pano_ros::PanoCaptureFeedbackConstPtr &  feedback) [private]

Triggered while the pano_ros server is gathering snapshots

Parameters:
feedback

Definition at line 373 of file panorama.cpp.

Checks, if the robot has turned the specified angle interval

Definition at line 192 of file panorama.cpp.

Definition at line 69 of file panorama.cpp.

Additionally sends out logging information on a ROS topic

Parameters:
msglogging information

Definition at line 407 of file panorama.cpp.

void turtlebot_panorama::PanoApp::odomCb ( const nav_msgs::OdometryConstPtr &  msg) [private]

Processes the robot's odometry data

Parameters:
msgodometry data

Definition at line 205 of file panorama.cpp.

Rotates the robot

Definition at line 186 of file panorama.cpp.

Takes a snapshot

Definition at line 180 of file panorama.cpp.

Definition at line 113 of file panorama.cpp.

Sends an action to goal the pano_ros action server for taking snapshots and stitching them together

Definition at line 337 of file panorama.cpp.

void turtlebot_panorama::PanoApp::stitchedImageCb ( const sensor_msgs::ImageConstPtr &  msg) [private]

Receives the stitched panorama picture

Parameters:
msgstiched image

Definition at line 395 of file panorama.cpp.

Stops the taking snapshots and triggers the stitching

Definition at line 351 of file panorama.cpp.

void turtlebot_panorama::PanoApp::stopPanoCb ( const std_msgs::EmptyConstPtr &  msg) [private]

Stops the panorama creation

Parameters:
msgempty message

Definition at line 320 of file panorama.cpp.

void turtlebot_panorama::PanoApp::takePanoCb ( const std_msgs::EmptyConstPtr &  msg) [private]

Simple way of taking a panorama picture (uses default values)

Parameters:
msgempty message

Definition at line 293 of file panorama.cpp.

bool turtlebot_panorama::PanoApp::takePanoServiceCb ( turtlebot_msgs::TakePanorama::Request &  request,
turtlebot_msgs::TakePanorama::Response &  response 
) [private]

Starts the creation of a panorama picture via a ROS service

Parameters:
requestspecify the details for panorama creation
responsethe current state of the app (started, in progress, stopped)
Returns:
true, if service call was successful

Definition at line 233 of file panorama.cpp.


Member Data Documentation

Definition at line 90 of file panorama.h.

Definition at line 90 of file panorama.h.

geometry_msgs::Twist turtlebot_panorama::PanoApp::cmd_vel [private]

Definition at line 88 of file panorama.h.

Definition at line 92 of file panorama.h.

Default panorama mode used for interaction via rostopic

Definition at line 136 of file panorama.h.

Default panorama angle used for interaction via rostopic

Definition at line 140 of file panorama.h.

Default rotation velocity used for interaction via rostopic

Definition at line 148 of file panorama.h.

Default snap interval used for interaction via rostopic

Definition at line 144 of file panorama.h.

std_msgs::Empty turtlebot_panorama::PanoApp::empty_msg [private]

Definition at line 87 of file panorama.h.

Definition at line 90 of file panorama.h.

Tells the pano_ros feedback callback to set is_active to true (starts rotating the robot) This is necessary in order to capture the first picture at the start, since it takes a while to get the first pciture from the Kinect.

Definition at line 132 of file panorama.h.

turns true, when the pano_ros action goal goes active

Definition at line 126 of file panorama.h.

Definition at line 90 of file panorama.h.

Definition at line 84 of file panorama.h.

Definition at line 114 of file panorama.h.

Definition at line 86 of file panorama.h.

Definition at line 85 of file panorama.h.

Definition at line 116 of file panorama.h.

for stop the pano_ros action goal; triggers the stitching of the gathered snapshots

Definition at line 120 of file panorama.h.

Definition at line 108 of file panorama.h.

Definition at line 106 of file panorama.h.

Definition at line 102 of file panorama.h.

Definition at line 89 of file panorama.h.

Definition at line 96 of file panorama.h.

Definition at line 110 of file panorama.h.

Definition at line 98 of file panorama.h.

Definition at line 122 of file panorama.h.

Definition at line 100 of file panorama.h.

geometry_msgs::Twist turtlebot_panorama::PanoApp::zero_cmd_vel [private]

Definition at line 88 of file panorama.h.


The documentation for this class was generated from the following files:


turtlebot_panorama
Author(s): Younghun Ju, Jihoon Lee, Marcus Liebhardt
autogenerated on Mon Mar 14 2016 10:57:25