Public Member Functions | |
virtual void | onInit () |
Private Member Functions | |
void | connectCb (const image_transport::SingleSubscriberPublisher &ssp) |
void | disconnectCb (const image_transport::SingleSubscriberPublisher &) |
void | do_work (const sensor_msgs::ImageConstPtr &msg, const std::string input_frame_from_msg) |
const std::string & | frameWithDefault (const std::string &frame, const std::string &image_frame) |
void | imageCallback (const sensor_msgs::ImageConstPtr &msg) |
void | imageCallbackWithInfo (const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info) |
void | reconfigureCallback (image_rotate::ImageRotateConfig &new_config, uint32_t level) |
void | setupTFListener () |
void | subscribe () |
void | transformVector (const std::string &input_frame_id, const ros::Time &target_time, const std::string &source_frame_id, const ros::Time &time, const std::string &fixed_frame_id, const tf::Stamped< tf::Vector3 > &input_vector, tf::Stamped< tf::Vector3 > &target_vector, const ros::Duration &duration) |
void | unsubscribe () |
Private Attributes | |
double | angle_ |
image_transport::CameraSubscriber | cam_sub_ |
image_rotate::ImageRotateConfig | config_ |
image_transport::Publisher | img_pub_ |
image_transport::Subscriber | img_sub_ |
boost::shared_ptr < image_transport::ImageTransport > | it_ |
ros::NodeHandle | nh_ |
ros::Time | prev_stamp_ |
tf::Stamped< tf::Vector3 > | source_vector_ |
dynamic_reconfigure::Server < image_rotate::ImageRotateConfig > | srv |
int | subscriber_count_ |
tf::Stamped< tf::Vector3 > | target_vector_ |
boost::shared_ptr < tf2::BufferClient > | tf2_client_ |
tf::TransformBroadcaster | tf_pub_ |
boost::shared_ptr < tf::TransformListener > | tf_sub_ |
bool | use_tf2_ |
Definition at line 61 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::connectCb | ( | const image_transport::SingleSubscriberPublisher & | ssp | ) | [inline, private] |
Definition at line 295 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::disconnectCb | ( | const image_transport::SingleSubscriberPublisher & | ) | [inline, private] |
Definition at line 302 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::do_work | ( | const sensor_msgs::ImageConstPtr & | msg, |
const std::string | input_frame_from_msg | ||
) | [inline, private] |
Definition at line 164 of file image_rotate_nodelet.cpp.
const std::string& image_rotate::ImageRotateNodelet::frameWithDefault | ( | const std::string & | frame, |
const std::string & | image_frame | ||
) | [inline, private] |
Definition at line 115 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline, private] |
Definition at line 127 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::imageCallbackWithInfo | ( | const sensor_msgs::ImageConstPtr & | msg, |
const sensor_msgs::CameraInfoConstPtr & | cam_info | ||
) | [inline, private] |
Definition at line 122 of file image_rotate_nodelet.cpp.
virtual void image_rotate::ImageRotateNodelet::onInit | ( | ) | [inline, virtual] |
Implements nodelet::Nodelet.
Definition at line 311 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::reconfigureCallback | ( | image_rotate::ImageRotateConfig & | new_config, |
uint32_t | level | ||
) | [inline, private] |
Definition at line 99 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::setupTFListener | ( | ) | [inline, private] |
Definition at line 84 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::subscribe | ( | ) | [inline, private] |
Definition at line 279 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::transformVector | ( | const std::string & | input_frame_id, |
const ros::Time & | target_time, | ||
const std::string & | source_frame_id, | ||
const ros::Time & | time, | ||
const std::string & | fixed_frame_id, | ||
const tf::Stamped< tf::Vector3 > & | input_vector, | ||
tf::Stamped< tf::Vector3 > & | target_vector, | ||
const ros::Duration & | duration | ||
) | [inline, private] |
Definition at line 132 of file image_rotate_nodelet.cpp.
void image_rotate::ImageRotateNodelet::unsubscribe | ( | ) | [inline, private] |
Definition at line 288 of file image_rotate_nodelet.cpp.
double image_rotate::ImageRotateNodelet::angle_ [private] |
Definition at line 81 of file image_rotate_nodelet.cpp.
Definition at line 72 of file image_rotate_nodelet.cpp.
image_rotate::ImageRotateConfig image_rotate::ImageRotateNodelet::config_ [private] |
Definition at line 67 of file image_rotate_nodelet.cpp.
Definition at line 70 of file image_rotate_nodelet.cpp.
Definition at line 71 of file image_rotate_nodelet.cpp.
boost::shared_ptr<image_transport::ImageTransport> image_rotate::ImageRotateNodelet::it_ [private] |
Definition at line 77 of file image_rotate_nodelet.cpp.
Reimplemented from nodelet::Nodelet.
Definition at line 78 of file image_rotate_nodelet.cpp.
Definition at line 82 of file image_rotate_nodelet.cpp.
tf::Stamped<tf::Vector3> image_rotate::ImageRotateNodelet::source_vector_ [private] |
Definition at line 75 of file image_rotate_nodelet.cpp.
dynamic_reconfigure::Server<image_rotate::ImageRotateConfig> image_rotate::ImageRotateNodelet::srv [private] |
Definition at line 68 of file image_rotate_nodelet.cpp.
int image_rotate::ImageRotateNodelet::subscriber_count_ [private] |
Definition at line 80 of file image_rotate_nodelet.cpp.
tf::Stamped<tf::Vector3> image_rotate::ImageRotateNodelet::target_vector_ [private] |
Definition at line 74 of file image_rotate_nodelet.cpp.
boost::shared_ptr<tf2::BufferClient> image_rotate::ImageRotateNodelet::tf2_client_ [private] |
Definition at line 66 of file image_rotate_nodelet.cpp.
Definition at line 65 of file image_rotate_nodelet.cpp.
boost::shared_ptr<tf::TransformListener> image_rotate::ImageRotateNodelet::tf_sub_ [private] |
Definition at line 64 of file image_rotate_nodelet.cpp.
bool image_rotate::ImageRotateNodelet::use_tf2_ [private] |
Definition at line 63 of file image_rotate_nodelet.cpp.