servo_pan_tilt.h
Go to the documentation of this file.
00001 
00012 #ifndef SERVO_PAN_TILT_H_
00013 #define SERVO_PAN_TILT_H_
00014 
00015 #include <ros/ros.h>
00016 #include <carl_dynamixel/LookAtFrame.h>
00017 #include <carl_dynamixel/LookAtPoint.h>
00018 #include <sensor_msgs/JointState.h>
00019 #include <std_msgs/Float64.h>
00020 #include <tf/transform_listener.h>
00021 
00022 #define ASUS_TILT_MIN -1.79
00023 #define ASUS_TILT_MAX 2.59
00024 
00032 class servoPanTilt
00033 {
00034 public:
00038   servoPanTilt();
00039 
00040 private:
00046   void backJointStateCallback(const sensor_msgs::JointState::ConstPtr& msg);
00047   
00053   void frontJointStateCallback(const sensor_msgs::JointState::ConstPtr& msg);
00054 
00059   void tiltCallback(const std_msgs::Float64::ConstPtr& msg);
00060   
00065   void panCallback(const std_msgs::Float64::ConstPtr& msg);
00066 
00073   bool lookAtPoint(carl_dynamixel::LookAtPoint::Request &req, carl_dynamixel::LookAtPoint::Response &res);
00074 
00081   bool lookAtFrame(carl_dynamixel::LookAtFrame::Request &req, carl_dynamixel::LookAtFrame::Response &res);
00082 
00089   float calculateLookAngle(float x, float z);
00090 
00091   ros::NodeHandle node; 
00093   ros::Publisher asusServoControllerPublisher; 
00094   ros::Publisher creativeServoControllerPublisher; 
00095   ros::Subscriber tiltCommandSubscriber; 
00096   ros::Subscriber panCommandSubscriber; 
00097   ros::Subscriber backJointStateSubscriber; 
00098   ros::Subscriber frontJointStateSubscriber; 
00100   ros::ServiceServer lookAtPointServer;
00101   ros::ServiceServer lookAtFrameServer;
00102 
00103   tf::TransformListener tfListener;
00104 
00105   float backServoPos; 
00106   float frontServoPos; 
00107 };
00108 
00109 #endif


carl_dynamixel
Author(s): Chris Dunkers , David Kent
autogenerated on Thu Jun 6 2019 21:09:46