00001
00008 #include <string>
00009 #include <ros/ros.h>
00010 #include <ptu46/ptu46_driver.h>
00011 #include <sensor_msgs/JointState.h>
00012
00013 namespace PTU46 {
00014
00034 class PTU46_Node {
00035 public:
00036 PTU46_Node(ros::NodeHandle& node_handle);
00037 ~PTU46_Node();
00038
00039
00040 void Connect();
00041 bool ok() {
00042 return m_pantilt != NULL;
00043 }
00044 void Disconnect();
00045
00046
00047 void spinOnce();
00048
00049
00050 void SetGoal(const sensor_msgs::JointState::ConstPtr& msg);
00051
00052 protected:
00053 PTU46* m_pantilt;
00054 ros::NodeHandle m_node;
00055 ros::Publisher m_joint_pub;
00056 ros::Subscriber m_joint_sub;
00057 };
00058
00059 PTU46_Node::PTU46_Node(ros::NodeHandle& node_handle)
00060 :m_pantilt(NULL), m_node(node_handle) {
00061
00062 }
00063
00064 PTU46_Node::~PTU46_Node() {
00065 Disconnect();
00066 }
00067
00070 void PTU46_Node::Connect() {
00071
00072 if (ok()) {
00073 Disconnect();
00074 }
00075
00076
00077 m_joint_pub = m_node.advertise
00078 <sensor_msgs::JointState>("state", 1);
00079
00080
00081 m_joint_sub = m_node.subscribe
00082 <sensor_msgs::JointState>("cmd", 1, &PTU46_Node::SetGoal, this);
00083
00084 ros::spin();
00085
00086
00087 std::string port;
00088 m_node.param<std::string>("port", port, PTU46_DEFAULT_PORT);
00089 int baud;
00090 m_node.param("baud", baud, PTU46_DEFAULT_BAUD);
00091
00092
00093 ROS_INFO("Attempting to connect to %s...", port.c_str());
00094 m_pantilt = new PTU46(port.c_str(), baud);
00095 ROS_ASSERT(m_pantilt != NULL);
00096 if (! m_pantilt->isOpen()) {
00097 ROS_ERROR("Could not connect to pan/tilt unit [%s]", port.c_str());
00098 Disconnect();
00099 return;
00100 }
00101 ROS_INFO("Connected!");
00102
00103 m_node.setParam("min_tilt", m_pantilt->GetMin(PTU46_TILT));
00104 m_node.setParam("max_tilt", m_pantilt->GetMax(PTU46_TILT));
00105 m_node.setParam("min_tilt_speed", m_pantilt->GetMinSpeed(PTU46_TILT));
00106 m_node.setParam("max_tilt_speed", m_pantilt->GetMaxSpeed(PTU46_TILT));
00107 m_node.setParam("tilt_step", m_pantilt->GetResolution(PTU46_TILT));
00108
00109 m_node.setParam("min_pan", m_pantilt->GetMin(PTU46_PAN));
00110 m_node.setParam("max_pan", m_pantilt->GetMax(PTU46_PAN));
00111 m_node.setParam("min_pan_speed", m_pantilt->GetMinSpeed(PTU46_PAN));
00112 m_node.setParam("max_pan_speed", m_pantilt->GetMaxSpeed(PTU46_PAN));
00113 m_node.setParam("pan_step", m_pantilt->GetResolution(PTU46_PAN));
00114
00115
00116
00117 m_joint_pub = m_node.advertise
00118 <sensor_msgs::JointState>("state", 1);
00119
00120
00121 m_joint_sub = m_node.subscribe
00122 <sensor_msgs::JointState>("cmd", 1, &PTU46_Node::SetGoal, this);
00123
00124 }
00125
00127 void PTU46_Node::Disconnect() {
00128 if (m_pantilt != NULL) {
00129 delete m_pantilt;
00130 m_pantilt = NULL;
00131 }
00132 }
00133
00135 void PTU46_Node::SetGoal(const sensor_msgs::JointState::ConstPtr& msg) {
00136 if (! ok())
00137 return;
00138
00139 bool set_pan_pos=false, set_tilt_pos=false, set_pan_speed=false, set_tilt_speed=false;
00140 double panpos, tiltpos, panspeed, tiltspeed;
00141
00142 for (size_t i=0; i<msg->name.size(); i++)
00143 {
00144 if (msg->name[i]==ros::names::remap("pan"))
00145 {
00146 if (msg->position.size()>i)
00147 {
00148 panpos=msg->position[i];
00149 set_pan_pos = true;
00150 }
00151
00152 if (msg->velocity.size()>i)
00153 {
00154 panspeed=msg->velocity[i];
00155 set_pan_speed = true;
00156 }
00157 }
00158
00159
00160 if (msg->name[i]==ros::names::remap("tilt"))
00161 {
00162 if (msg->position.size()>i)
00163 {
00164 tiltpos=msg->position[i];
00165 set_tilt_pos = true;
00166 }
00167
00168 if (msg->velocity.size()>i)
00169 {
00170 tiltspeed=msg->velocity[i];
00171 set_tilt_speed = true;
00172 }
00173 }
00174
00175 }
00176
00177 if (set_pan_pos)
00178 m_pantilt->SetPosition(PTU46_PAN, panpos);
00179
00180 if (set_tilt_pos)
00181 m_pantilt->SetPosition(PTU46_TILT, tiltpos);
00182
00183 if (set_pan_speed)
00184 m_pantilt->SetSpeed(PTU46_PAN, panspeed);
00185
00186 if (set_tilt_speed)
00187 m_pantilt->SetSpeed(PTU46_TILT, tiltspeed);
00188 }
00189
00194 void PTU46_Node::spinOnce() {
00195 if (! ok())
00196 return;
00197
00198
00199 double pan = m_pantilt->GetPosition(PTU46_PAN);
00200 double tilt = m_pantilt->GetPosition(PTU46_TILT);
00201
00202 double panspeed = m_pantilt->GetSpeed(PTU46_PAN);
00203 double tiltspeed = m_pantilt->GetSpeed(PTU46_TILT);
00204
00205
00206 sensor_msgs::JointState joint_state;
00207 joint_state.header.stamp = ros::Time::now();
00208
00209
00210
00211 joint_state.name[0] =ros::names::remap("pan");
00212 joint_state.position[0] = pan;
00213 joint_state.velocity[0] = panspeed;
00214 joint_state.name[1] =ros::names::remap("tilt");
00215 joint_state.position[1] = tilt;
00216 joint_state.velocity[1] = tiltspeed;
00217 m_joint_pub.publish(joint_state);
00218
00219 }
00220
00221 }
00222
00223 int main(int argc, char** argv) {
00224 ros::init(argc, argv, "ptu");
00225 ros::NodeHandle n("~");
00226
00227
00228 PTU46::PTU46_Node ptu_node = PTU46::PTU46_Node(n);
00229 ptu_node.Connect();
00230 if (! ptu_node.ok())
00231 return -1;
00232
00233
00234 int hz;
00235 n.param("hz", hz, PTU46_DEFAULT_HZ);
00236 ros::Rate loop_rate(hz);
00237
00238 while (ros::ok() && ptu_node.ok()) {
00239
00240 ptu_node.spinOnce();
00241
00242
00243 ros::spinOnce();
00244
00245
00246 loop_rate.sleep();
00247 }
00248
00249 if (! ptu_node.ok()) {
00250 ROS_ERROR("pan/tilt unit disconncted prematurely");
00251 return -1;
00252 }
00253
00254 return 0;
00255 }