state_example.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 #ifndef _atlascar_transforms_CPP_
28 #define _atlascar_transforms_CPP_
29 
40 #include "state_example.h"
41 
42 #include <string>
43 #include <ros/ros.h>
44 #include <sensor_msgs/JointState.h>
45 #include <tf/transform_broadcaster.h>
46 
47 int main(int argc, char **argv)
48 {
49  ros::init(argc, argv, "atlascar_transforms"); // Initialize ROS coms
50  ros::NodeHandle n; //The node handle
51  p_node = &n;
52  ros::Rate loop_rate(1);
53 
54  tf::Vector3 V(-1.8583, 0, 0.9927);
55  tf::Matrix3x3 M(0.9744, 0, 0.2250, 0, 1, 0, -0.225, 0, 0.9744);
56  double r,p,y;
57 #if ROS_VERSION_MINIMUM(1, 8, 0) // if current ros version is >= 1.8.0
58  M.getEulerYPR(y, p, r); //Changed by V. Santos, 15-Abr-2013,09:11
59 #else // Code for earlier versions (Electric, diamondback, ...)
60  M.getRPY(r,p,y);
61 #endif
62  ROS_INFO("Link position (to copy paste directly to urdf)");
63  ROS_INFO("xyz=\"%f %f %f\" rpy=\"%f %f %f\"", V[0], V[1], V[2], r,p,y);
64 
65  //TRANSFORM FROM LASER_LEFT_BUMPER to Vehicle (A transform that brings a point in)
66  tf::TransformBroadcaster tf_br1;
67  tf::Transform tr1 = tf::Transform(tf::Matrix3x3(0.8039, 0.5948, 0, -0.5948, 0.8039, 0, 0, 0, 1),
68  tf::Vector3(-0.08, 0.8350, 0));
69 
70  //TRANSFORM FROM LASER_RIGHT_BUMPER to Vehicle (A transform that brings a point in)
71  tf::TransformBroadcaster tf_br2;
72  tf::Transform tr2 = tf::Transform(tf::Matrix3x3(-0.8192,0.5736,0,-0.5736,-0.8192,0,0,0,1),
73  tf::Vector3(-0.12, -0.89, -0.0950));
74 
75  //TRANSFORM FROM LASER_ROOF_ROTATING_BASE to Vehicle (A transform that brings a point in)
76  tf::TransformBroadcaster tf_br3;
77  tf::Transform tr3 = tf::Transform(tf::Matrix3x3(0.9890,0.0129,0.1472,0.,0.9962,-0.0872,-0.1478,0.0862,0.9853),
78  tf::Vector3(-1.7803, 0, 1.1861));
79 
80  //TRANSFORM FROM XB3_right camera to Vehicle (A transform that brings a point in)
81 // tf::TransformBroadcaster tf_br4;
82 // tf::Transform tr4 = tf::Transform(tf::Matrix3x3(0,-0.1392, 0.9903 , -1, 0, 0, 0, -0.9903, -0.1392),
83 // tf::Vector3(-1.8405, 0.2400, 1.1170));
84 
85  //TRANSFORM FROM PTU base to Vehicle (A transform that brings a point in)
86 // tf::TransformBroadcaster tf_br5;
87 // tf::Transform tr5 = tf::Transform(tf::Matrix3x3(1,0,0,0,1,0,0,0,1),
88 // tf::Vector3(-1.877, -0.4920, 0.99));
89 
90  //TRANSFORM FROM Hokuyo laser to Vehicle (A transform that brings a point in)
91 // tf::TransformBroadcaster tf_br6;
92 // tf::Transform tr6 = tf::Transform(tf::Matrix3x3(0.9744, 0, 0.2250, 0, 1, 0, -0.225, 0, 0.9744),
93 // tf::Vector3(-1.8583, 0, 0.9927));
94 
95  ros::Publisher joint_pub = n.advertise<sensor_msgs::JointState>("joint_states", 1);
96  tf::TransformBroadcaster broadcaster;
97 
98  const double degree = M_PI/180;
99 
100  // robot state
101  double tilt = 0, tinc = degree, swivel=0, angle=0, height=0, hinc=0.005;
102 
103  // message declarations
104  geometry_msgs::TransformStamped odom_trans;
105  sensor_msgs::JointState joint_state;
106  odom_trans.header.frame_id = "odom";
107  odom_trans.child_frame_id = "axis";
108 
109  while (ros::ok()) {
110  //update joint_state
111  joint_state.header.stamp = ros::Time::now();
112  joint_state.name.resize(3);
113  joint_state.position.resize(3);
114  joint_state.name[0] ="swivel";
115  joint_state.position[0] = swivel;
116  joint_state.name[1] ="tilt";
117  joint_state.position[1] = tilt;
118  joint_state.name[2] ="periscope";
119  joint_state.position[2] = height;
120 
121 
122  // update transform
123  // (moving in a circle with radius=2)
124  odom_trans.header.stamp = ros::Time::now();
125  odom_trans.transform.translation.x = cos(angle)*2;
126  odom_trans.transform.translation.y = sin(angle)*2;
127  odom_trans.transform.translation.z = .7;
128  odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(angle+M_PI/2);
129 
130  //send the joint state and transform
131  joint_pub.publish(joint_state);
132  broadcaster.sendTransform(odom_trans);
133 
134  // Create new robot state
135  tilt += tinc;
136  if (tilt<-.5 || tilt>0) tinc *= -1;
137  height += hinc;
138  if (height>.2 || height<0) hinc *= -1;
139  swivel += degree;
140  angle += degree/4;
141 
142  // This will adjust as needed per iteration
143  loop_rate.sleep();
144  }
145 
146 
147  //JUST ADD the sensors here, their 6dof position, and add a transform broadcaster at the while cycle
148 
149  while (n.ok()) //CYCLE, because transforms are static, will publish a transform once a second
150  {
151 
152  tf_br1.sendTransform(tf::StampedTransform(tr1, ros::Time::now(), "/tf_atc/vehicle","/tf_atc/laser/left_bumper"));
153  tf_br2.sendTransform(tf::StampedTransform(tr2, ros::Time::now(), "/tf_atc/vehicle","/tf_atc/laser/right_bumper"));
154  tf_br3.sendTransform(tf::StampedTransform(tr3, ros::Time::now(), "/tf_atc/vehicle","/tf_atc/laser/roof_rotating_base"));
155  //tf_br4.sendTransform(tf::StampedTransform(tr4, ros::Time::now(), "/tf_atc/laser/roof_rotating_base","/tf_atc/laser/roof_rotating"));
156 
157  ros::spinOnce();
158  loop_rate.sleep();
159  }
160 
161  return 0;
162 }
163 #endif
_EXTERN_ ros::NodeHandle * p_node
Definition: state_example.h:82
int main(int argc, char **argv)
Deprecated example header.


atlascar_base
Author(s): Jorge Almeida, Sérgio Pinho, Miguel Oliveira, Pedro Salvado, Andre Oliveira and Pedro Pinheiro
autogenerated on Mon Mar 2 2015 01:31:23