laserscanner_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014, Osnabrueck University
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  * * Redistributions of source code must retain the above copyright notice,
00009  *   this list of conditions and the following disclaimer.
00010  * * Redistributions in binary form must reproduce the above copyright notice,
00011  *   this list of conditions and the following disclaimer in the documentation
00012  *   and/or other materials provided with the distribution.
00013  * * Neither the name of the Osnabrueck University nor the names of its
00014  *   contributors may be used to endorse or promote products derived from this
00015  *   software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 #include "kurt3d/ServoCommand.h"
00032 #include "kurt3d/Scan.h"
00033 #include <sensor_msgs/LaserScan.h>
00034 #include <laser_assembler/AssembleScans2.h>
00035 #include <cstdlib>
00036 #define _USE_MATH_DEFINES
00037 
00038 
00039 #define MIN_POS ((50.0 * (float)M_PI) / 180.0)
00040 #define STANDBY_POS ((20.0 * (float)M_PI) / 180.0)
00041 #define MAX_POS ((-60.0 * (float)M_PI) / 180.0)
00042 #define RANGE 1000
00043 
00044 static ros::ServiceClient client;
00045 static ros::ServiceClient pointCloudClient;
00046 
00047 static ros::Publisher state_pub;
00048 static ros::Publisher laser_pub;
00049 
00050 static sensor_msgs::LaserScan lastPublishedScan;
00051 
00052 static sensor_msgs::LaserScan currentScan;
00053 static sensor_msgs::LaserScan lastScan;
00054 
00055 void scanCallback(const sensor_msgs::LaserScan::ConstPtr& msg)
00056 {
00057   lastScan = currentScan;
00058   currentScan = *msg;
00059 }
00060 
00061 
00062 bool scan(kurt3d::Scan::Request  &req,
00063          kurt3d::Scan::Response &res)
00064 {
00065     std::cout << "Min Pos" << std::endl;
00066     kurt3d::ServoCommand srv;
00067 
00068     srv.request.joint_goal.name.resize(1);
00069     srv.request.joint_goal.position.resize(1);
00070     srv.request.joint_goal.velocity.resize(1);
00071     srv.request.joint_goal.effort.resize(1);
00072     srv.request.joint_goal.name[0] = "drehobjekt_1_to_balken_1";
00073     srv.request.joint_goal.position[0] = MIN_POS;
00074     srv.request.joint_goal.velocity[0] = 1.5;
00075 
00076     if (client.call(srv))
00077     {
00078       ROS_INFO("Movement finished");
00079     }
00080     else
00081     {
00082       ROS_ERROR("Failed to call service servo_command");
00083       return 1;
00084     }
00085 
00086     laser_assembler::AssembleScans2 assemble_srv;
00087     assemble_srv.request.begin = ros::Time::now();
00088     ros::Rate loop_rate(150);
00089 
00090     for(int i = 0; i < RANGE && ros::ok(); i++)
00091     {
00092         float angle;
00093 
00094         angle = MIN_POS+ (float)i/ (float)RANGE * (MAX_POS-MIN_POS);
00095 
00096         ROS_INFO("angle: [%f]",angle);
00097 
00098         std::cout << "Angle: " << angle << std::endl;
00099 
00100         srv.request.joint_goal.position[0] = angle;
00101         srv.request.joint_goal.velocity[0] = 0.5;
00102 
00103         if (client.call(srv))
00104         {
00105           ROS_INFO("Movement finished");
00106 
00107           while(ros::ok() && (lastPublishedScan.header.seq == currentScan.header.seq || lastPublishedScan.header.seq == lastScan.header.seq))
00108           {
00109               ros::spinOnce();
00110               loop_rate.sleep();
00111           }
00112 
00113           laser_pub.publish(lastScan);
00114           std::cout << "" << lastScan.header.seq << std::endl;
00115           laser_pub.publish(currentScan);
00116           std::cout << currentScan.header.seq << std::endl;
00117           lastPublishedScan = currentScan;
00118         }
00119         else
00120         {
00121           ROS_ERROR("Failed to call service servo nodding");
00122           return 1;
00123         }
00124 
00125         ros::spinOnce();
00126     };
00127 
00128 
00129 
00130     assemble_srv.request.end = ros::Time::now();
00131 
00132     if (pointCloudClient.call(assemble_srv))
00133     {
00134         ROS_INFO("Scan assembled");
00135 
00136         state_pub.publish(assemble_srv.response.cloud);
00137     }
00138     else
00139     {
00140       ROS_ERROR("Failed to call service assemble_scans");
00141       return 1;
00142     }
00143 
00144 
00145     srv.request.joint_goal.position[0] = STANDBY_POS;
00146     srv.request.joint_goal.velocity[0] = 1.0;
00147 
00148     if (client.call(srv))
00149     {
00150       ROS_INFO("Movement finished");
00151     }
00152     else
00153     {
00154       ROS_ERROR("Failed to call service servo nodding");
00155       return 1;
00156     }
00157 
00158 
00159 
00160 
00161     res.finished = true;
00162     return true;
00163 }
00164 
00165 int main(int argc, char **argv)
00166 {
00167   ros::init(argc, argv, "laserscanner_node");
00168 
00169 
00170   ros::NodeHandle n;
00171 
00172   client = n.serviceClient<kurt3d::ServoCommand>("servo_node");
00173 
00174   ROS_INFO("Waiting for [assemble_scans2] to be advertised");
00175   ros::service::waitForService("assemble_scans2");
00176   ROS_INFO("Found assemble_scans2! Starting the laserscanner_node");
00177   pointCloudClient = n.serviceClient<laser_assembler::AssembleScans2>("assemble_scans2");
00178 
00179   // inits the publisher
00180   state_pub = n.advertise<sensor_msgs::PointCloud2>("uos_3dscans", 1);
00181 
00182   // inits the publisher
00183   laser_pub = n.advertise<sensor_msgs::LaserScan>("cleaned_scan", 100);
00184 
00185   // inits the subscriber
00186   ros::Subscriber sub = n.subscribe("scan", 100, scanCallback);
00187 
00188 
00189   // inits the service
00190   ros::ServiceServer service = n.advertiseService("laserscanner_node", scan);
00191 
00192 
00193   ROS_INFO("laser scanner server ready to laser scan");
00194   ros::spin();
00195   return 0;
00196 }


kurt3d
Author(s): Thomas Wiemann, Benjamin Kisliuk, Alexander Mock
autogenerated on Wed Sep 16 2015 10:24:29