laser_rotate3D.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011 LAR-DEM-University of Aveiro.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of LAR-DEM-University of Aveiro nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33 */
34 
41 #ifndef _LASER_ROTATE3D_CPP_
42 #define _LASER_ROTATE3D_CPP_
43 
44 //system includes
45 
46 #include <termios.h>
47 #include <stdio.h>
48 #include <fcntl.h>
49 #include <termio.h>
50 #include <unistd.h>
51 #include <stdlib.h>
52 #include <sys/ioctl.h>
53 #include <stdint.h>
54 #include <stdlib.h>
55 
56 #include <string.h>
57 #include <errno.h>
58 #include <math.h>
59 #include <poll.h>
60 #include <signal.h>
61 #include <iostream>
62 #include <fstream>
63 
64 // ROS
65 #include <ros/ros.h>
66 #include <sensor_msgs/JointState.h>
67 #include <std_msgs/String.h>
68 #include <tf/transform_broadcaster.h>
69 
70 //LAR3 includes
71 #include <serialcom/SerialCom.h>
72 
73 //Local includes
75 
76 //using namespace std;
77 
78 //void RotateLaser::RotateLaserCallback(std::string* readdata)
79 // this function is called back once the readline thread is invoked
80 //void RotateLaserCallback(std::string* readdata)
81 //{
82 // int thesize;
83 // thesize = readdata->size();
84 // // for now print on screen what has been read
85 // printf("string size %s \n", readdata->c_str());//readdata->c_str);
86 //
87  // have to pass the information in order to safely allow publishing
88 
89 //};
90 
91 int main(int argc, char ** argv)
92 {
93 
94  ros::init(argc,argv,"RotateLaser");
95  ros::Time::init(); // only to be used in testing and standalone.
96  ros::Rate loop_rate(200); //it was 100
97 
98  //int baudrate = 9600;
99 
100  // instatiate the RotateLaser
101  RotateLaser RotateTheLaser;
102 
103  /* assign a callback for reading the serial port: use binding because we are
104  invoking a member function and boost does not support that directly
105  http://www.boost.org/doc/libs/1_48_0/doc/html/function/tutorial.html
106  http://www.boost.org/doc/libs/1_48_0/libs/bind/bind.html#with_member_pointers */
107  RotateTheLaser.BoostRotateLaserCallback = std::bind1st(std::mem_fun(&RotateLaser::RotateLaserCallback), &RotateTheLaser); //&RotateLaserCallback;
108 
109  // has to read from the PIC via serial port and publish
110  // start a thread for reading the serial port
111  RotateTheLaser.ReadLinesSerialPort(RotateTheLaser.BoostRotateLaserCallback);
112 
113 
114 // while(ros::ok()) //this was uncomment
115 // { //this was uncomment
116  ros::spin();
117 // printf("this is %s \n", "test");
118 // RotateTheLaser.SendCommand();
119 // RotateTheLaser.Publish(); // this will publish the angle at the desired rate //this was uncomment
120 // ros::spinOnce(); //this was uncomment
121 // loop_rate.sleep(); //this was uncomment
122 // };
123 
124  return 0;
125 
126 }
127 
128 #endif //EOF
void RotateLaserCallback(std::string *readdata)
void ReadLinesSerialPort(boost::function< void(std::string *)> f)
ReadLinesSerialPort thread to read from the serial port, inherited from SerialCom.
int main(int argc, char **argv)
boost::function< void(std::string *)> BoostRotateLaserCallback
class implements a gateway to communicate with the PIC to rotate the LMS200


laser_rotate_3d
Author(s): Ricardo Pascoal
autogenerated on Mon Mar 2 2015 01:32:06