#include <panorama.h>
Public Member Functions | |
void | init () |
void | log (std::string msg) |
PanoApp () | |
void | spin () |
~PanoApp () | |
Private Member Functions | |
void | cameraImageCb (const sensor_msgs::ImageConstPtr &msg) |
bool | hasReachedAngle () |
void | odomCb (const nav_msgs::OdometryConstPtr &msg) |
void | rotate () |
void | snap () |
void | startPanoAction () |
bool | takePanoServiceCb (turtlebot3_applications_msgs::TakePanorama::Request &request, turtlebot3_applications_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 |
double | given_angle |
bool | go_active |
std::vector< cv::Mat > | images_ |
bool | is_active |
double | last_angle |
ros::NodeHandle | nh |
std::map< std::string, std::string > | params |
ros::NodeHandle | priv_nh |
ros::Publisher | pub_cmd_vel |
image_transport::Publisher | pub_stitched |
double | snap_interval |
ros::ServiceServer | srv_start_pano |
bool | store_image |
image_transport::Subscriber | sub_camera |
ros::Subscriber | sub_odom |
geometry_msgs::Twist | zero_cmd_vel |
The PanoApp utilises pano_ros for creating panorama pictures.
Definition at line 68 of file panorama.h.
turtlebot_panorama::PanoApp::PanoApp | ( | ) |
Definition at line 51 of file panorama.cpp.
turtlebot_panorama::PanoApp::~PanoApp | ( | ) |
Definition at line 56 of file panorama.cpp.
|
private |
Definition at line 295 of file panorama.cpp.
|
private |
Definition at line 194 of file panorama.cpp.
void turtlebot_panorama::PanoApp::init | ( | ) |
Definition at line 61 of file panorama.cpp.
void turtlebot_panorama::PanoApp::log | ( | std::string | msg | ) |
Additionally sends out logging information on a ROS topic
msg | logging information |
Definition at line 326 of file panorama.cpp.
|
private |
Definition at line 207 of file panorama.cpp.
|
private |
Definition at line 188 of file panorama.cpp.
|
private |
Definition at line 180 of file panorama.cpp.
void turtlebot_panorama::PanoApp::spin | ( | ) |
Definition at line 95 of file panorama.cpp.
|
private |
|
private |
Starts the creation of a panorama picture via a ROS service
request | specify the details for panorama creation |
response | the current state of the app (started, in progress, stopped) |
Definition at line 235 of file panorama.cpp.
|
private |
Definition at line 90 of file panorama.h.
|
private |
Definition at line 90 of file panorama.h.
|
private |
Definition at line 88 of file panorama.h.
|
private |
Definition at line 92 of file panorama.h.
|
private |
Default panorama mode used for interaction via rostopic
Definition at line 119 of file panorama.h.
|
private |
Default panorama angle used for interaction via rostopic
Definition at line 123 of file panorama.h.
|
private |
Default rotation velocity used for interaction via rostopic
Definition at line 131 of file panorama.h.
|
private |
Default snap interval used for interaction via rostopic
Definition at line 127 of file panorama.h.
|
private |
Definition at line 90 of file panorama.h.
|
private |
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 115 of file panorama.h.
|
private |
Definition at line 104 of file panorama.h.
|
private |
turns true, when the pano_ros action goal goes active
Definition at line 109 of file panorama.h.
|
private |
Definition at line 90 of file panorama.h.
|
private |
Definition at line 84 of file panorama.h.
|
private |
Definition at line 86 of file panorama.h.
|
private |
Definition at line 85 of file panorama.h.
|
private |
Definition at line 100 of file panorama.h.
|
private |
Definition at line 94 of file panorama.h.
|
private |
Definition at line 89 of file panorama.h.
|
private |
Definition at line 97 of file panorama.h.
|
private |
Definition at line 133 of file panorama.h.
|
private |
Definition at line 95 of file panorama.h.
|
private |
Definition at line 102 of file panorama.h.
|
private |
Definition at line 88 of file panorama.h.