00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef _atlascar_transforms_CPP_
00028 #define _atlascar_transforms_CPP_
00029
00040 #include "state_example.h"
00041
00042 #include <string>
00043 #include <ros/ros.h>
00044 #include <sensor_msgs/JointState.h>
00045 #include <tf/transform_broadcaster.h>
00046
00047 int main(int argc, char **argv)
00048 {
00049 ros::init(argc, argv, "atlascar_transforms");
00050 ros::NodeHandle n;
00051 p_node = &n;
00052 ros::Rate loop_rate(1);
00053
00054 tf::Vector3 V(-1.8583, 0, 0.9927);
00055 tf::Matrix3x3 M(0.9744, 0, 0.2250, 0, 1, 0, -0.225, 0, 0.9744);
00056 double r,p,y;
00057 #if ROS_VERSION_MINIMUM(1, 8, 0) // if current ros version is >= 1.8.0
00058 M.getEulerYPR(y, p, r);
00059 #else // Code for earlier versions (Electric, diamondback, ...)
00060 M.getRPY(r,p,y);
00061 #endif
00062 ROS_INFO("Link position (to copy paste directly to urdf)");
00063 ROS_INFO("xyz=\"%f %f %f\" rpy=\"%f %f %f\"", V[0], V[1], V[2], r,p,y);
00064
00065
00066 tf::TransformBroadcaster tf_br1;
00067 tf::Transform tr1 = tf::Transform(tf::Matrix3x3(0.8039, 0.5948, 0, -0.5948, 0.8039, 0, 0, 0, 1),
00068 tf::Vector3(-0.08, 0.8350, 0));
00069
00070
00071 tf::TransformBroadcaster tf_br2;
00072 tf::Transform tr2 = tf::Transform(tf::Matrix3x3(-0.8192,0.5736,0,-0.5736,-0.8192,0,0,0,1),
00073 tf::Vector3(-0.12, -0.89, -0.0950));
00074
00075
00076 tf::TransformBroadcaster tf_br3;
00077 tf::Transform tr3 = tf::Transform(tf::Matrix3x3(0.9890,0.0129,0.1472,0.,0.9962,-0.0872,-0.1478,0.0862,0.9853),
00078 tf::Vector3(-1.7803, 0, 1.1861));
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095 ros::Publisher joint_pub = n.advertise<sensor_msgs::JointState>("joint_states", 1);
00096 tf::TransformBroadcaster broadcaster;
00097
00098 const double degree = M_PI/180;
00099
00100
00101 double tilt = 0, tinc = degree, swivel=0, angle=0, height=0, hinc=0.005;
00102
00103
00104 geometry_msgs::TransformStamped odom_trans;
00105 sensor_msgs::JointState joint_state;
00106 odom_trans.header.frame_id = "odom";
00107 odom_trans.child_frame_id = "axis";
00108
00109 while (ros::ok()) {
00110
00111 joint_state.header.stamp = ros::Time::now();
00112 joint_state.name.resize(3);
00113 joint_state.position.resize(3);
00114 joint_state.name[0] ="swivel";
00115 joint_state.position[0] = swivel;
00116 joint_state.name[1] ="tilt";
00117 joint_state.position[1] = tilt;
00118 joint_state.name[2] ="periscope";
00119 joint_state.position[2] = height;
00120
00121
00122
00123
00124 odom_trans.header.stamp = ros::Time::now();
00125 odom_trans.transform.translation.x = cos(angle)*2;
00126 odom_trans.transform.translation.y = sin(angle)*2;
00127 odom_trans.transform.translation.z = .7;
00128 odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(angle+M_PI/2);
00129
00130
00131 joint_pub.publish(joint_state);
00132 broadcaster.sendTransform(odom_trans);
00133
00134
00135 tilt += tinc;
00136 if (tilt<-.5 || tilt>0) tinc *= -1;
00137 height += hinc;
00138 if (height>.2 || height<0) hinc *= -1;
00139 swivel += degree;
00140 angle += degree/4;
00141
00142
00143 loop_rate.sleep();
00144 }
00145
00146
00147
00148
00149 while (n.ok())
00150 {
00151
00152 tf_br1.sendTransform(tf::StampedTransform(tr1, ros::Time::now(), "/tf_atc/vehicle","/tf_atc/laser/left_bumper"));
00153 tf_br2.sendTransform(tf::StampedTransform(tr2, ros::Time::now(), "/tf_atc/vehicle","/tf_atc/laser/right_bumper"));
00154 tf_br3.sendTransform(tf::StampedTransform(tr3, ros::Time::now(), "/tf_atc/vehicle","/tf_atc/laser/roof_rotating_base"));
00155
00156
00157 ros::spinOnce();
00158 loop_rate.sleep();
00159 }
00160
00161 return 0;
00162 }
00163 #endif