[ros-users] sensor origin

Eitan Marder-Eppstein eitan at willowgarage.com
Tue Aug 31 16:10:14 UTC 2010


Safdar,

Its possible that with the rates you posted for your transform and your
setting of the transform_tolerance parameter on the costmap, that things are
timing out. Can you post a couple of examples of the full "Costmap2dROS
transform timeout" error along with the configuration files that you're
using to bring up the navigation stack. Those two things should help track
this down.

Hope all is well,

Eitan

On Tue, Aug 31, 2010 at 8:09 AM, safdar_zaman <safdaraslam at yahoo.com> wrote:

>
> Hi Enea Scioni,
> Thanks for so detailed answer: I followed your instruction and just
> experimented again, following are the findings:
> RosAria:
> First RosAria is a node which enables us to move Real Robot (poineer P3DX),
> It subscribes a topic /cmd_vel with geometry_msgs/Twist message.
> some code from RosAria:
> {
>  pos = robot->getPose();
>  tf::poseTFToMsg(tf::Pose(tf::Quaternion(pos.getTh()*M_PI/180, 0, 0),
> tf::Vector3(pos.getX(), pos.getY(), 0)),
>  position.pose.pose);
>  position.twist.twist.linear.x = robot->getVel();
>  position.twist.twist.angular.z = robot->getRotVel()*M_PI/180;
>  position.header.frame_id = "odom";
>  position.header.stamp = ros::Time::now();
>  pose_pub.publish(position);
>  ROS_INFO("rcv: %f %f %f p.x: %f p.y: %f", position.header.stamp.toSec(),
> (double) position.twist.twist.linear.x,
>  (double)   position.twist.twist.angular.z, (double) pos.getX(), (double)
> pos.getY());
>  ros::Duration(1e-3).sleep();
>    tf::Quaternion laserQ;
>    laserQ.setRPY(0.0, 0.0, pos.getTh());
>    tf::Transform txLaser =  tf::Transform(laserQ,tf::Point(0.05, 0.0,
> 0.15));
>    tf.sendTransform(tf::StampedTransform(txLaser, ros::Time::now(),
> "base_link", "laser"));//"base_laser_link"));
>    tf::Transform txIdentity(tf::createIdentityQuaternion(),
>                             tf::Point(0.0, 0.0, 0.0));
>    tf.sendTransform(tf::StampedTransform(txIdentity,
>                                          ros::Time::now(),
>                                          "base_footprint",
>                                          "base_link"));
>    tf::Quaternion odomQ;
>     tf::quaternionMsgToTF(position.pose.pose.orientation, odomQ);
>    tf::Transform txOdom(odomQ, tf::Point((double) pos.getX()/1000.0,
> (double) pos.getY()/1000.0, pos.getTh()/*0.0*/));
>    tf.sendTransform(tf::StampedTransform(txOdom, ros::Time::now() ,"odom",
> "base_footprint"));
>   clockMsg.clock = ros::Time::now();
>   clock_pub.publish(clockMsg);
> }
> I run this node using [$rosrun ROSARIA RosAria _port:=/dev/ttyUSB0] then
> this node starts and subscribes the topic /cmd_vel. Then I run my own made
> node [$rosrun ROSARIA rob_key] which publishes geometry_msgs/Twist taking
> commands by arrow keys of keyboard.
>
> Frames:
> I checked frames by [$rosrun tf view_frames],  the frame's sequence is
> correct and quite according to how you said, i.e.
> with names and sequence : /map->/odom->/base_footprint->base_link->/laser
> shown in frames.pdf.
> map->odom : Broadcaster: /amcl , Average rate: 4.890 Hz, Most recent
> transform: 0.155 sec old, Buffer length: 4.908 sec
> odom->base_footprnt:Broadcaster:/RosAria,Average rate:10.204 Hz,Most recent
> transform: 0.063 sec old,Buffer length: 4.900 sec
> base_footprnt->base_link:same as above for odom->base_footprint
> base_link->laser:same as above for base_footprint-> base_link
>
> Sequence of the nodes I run:
> 1.$roscore
> 2.$rosrun ROSARIA RosAria _port:=/dev/ttyUSB0
> 3.$rosrun sicktoolbox_wrapper sicklms _port:=/dev/ttyUSB1 _baud:=38400
> get message DataStream Received.
> 4.$roslaunch amcl_diff.launch  from amcl/axamples> directory.
> get message
> [ WARN] [1283264052.917100260]: Request for map failed; trying again...
> [ WARN] [1283264053.418347837]: Request for map failed; trying again...
> [ WARN] [1283264053.926562217]: Request for map failed; trying again...
> [ INFO] [1283264054.545362657]: Received a 4000 X 4000 map @ 0.050 m/pix
>
> [ INFO] [1283264054.757590054]: map returned
> [ INFO] [1283264054.766719775]: Initializing likelihood field model; this
> can take some time on large maps...
> [ INFO] [1283264055.174108077]: Done initializing likelihood field model.
> [ WARN] [1283264055.247433315]: Message from [/sicklms] has a
> non-fully-qualified frame_id [laser]. Resolved locally to [/laser].  This
> is
> will likely not work in multi-robot systems.  This message will only print
> once.
> [ WARN] [1283264093.896718060]: Failed to transform initial pose in time
> (You requested a transform that is 0.065 miliseconds in the past,
> but the most recent transform in the tf buffer is 95.781 miliseconds old.
>  When trying to transform between /map and /base_link.
> )
> [ INFO] [1283264093.896820238]: Setting pose (1283264093.896801): 0.011
> -0.010 0.000
>
> 5.$rosrun map_server map_server map.yaml
> get message:
> [ INFO] [1283264053.796235254]: Loading map from image "./map.pgm"
> [ INFO] [1283264054.084837439]: Read a 4000 X 4000 map @ 0.050 m/cell
> [ INFO] [1283264054.449655659]: Sending map
>
> 6.$rosrun rviz rviz
> get message:
> [ INFO] [1283264081.753891609]: Loading general config from
> [/home/safdar/.rviz/config]
> [ INFO] [1283264081.754240117]: Loading display config from
> [/home/safdar/.rviz/display_config]
> [ INFO] [1283264093.894115354]: Setting pose: 0.011 -0.010 0.000
> [frame=/map]
>
> AND
> map.yaml contains:
> [image: map.pgm
> resolution: 0.050000
> origin: [-100.000000, -100.000000, 0.000000]
> #origin: [0.000000, 0.000000, 0.000000]
> negate: 0
> occupied_thresh: 0.65
> free_thresh: 0.196]
>
> THEN I MOVE ROBOT:
> Moving Robot almost 1 meter in forward direction:
> Starting till ending 1 meter motion of Robot ,I saved data from topics
> /odom, /scan, /amcl_pose and /particlecloud as given below:
>
> =====================================
> TOPIC /amcl_pose:
> ---
> header:
>  seq: 2
>  stamp:
>    secs: 1283264215
>    nsecs: 511374608
>  frame_id: map
> pose:
>  pose:
>    position:
>      x: 0.247589351646
>      y: -0.014679411528
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.00336333731185
>      w: 0.999994343965
>  covariance: [0.29763234232004948, 0.0025907719733360285, 0.0, 0.0, 0.0,
> 0.0, 0.0025907719733360285, 0.24746057733576973, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.083540103401309157, 0.0, 0.0,
> 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 3
>  stamp:
>    secs: 1283264216
>    nsecs: 151775071
>  frame_id: map
> pose:
>  pose:
>    position:
>      x: 0.497609492943
>      y: 0.0093983678752
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.00909101066835
>      w: 0.999958675909
>  covariance: [0.33799146489379533, 0.010049943074077266, 0.0, 0.0, 0.0,
> 0.0, 0.010049943074077266, 0.27290467320518264, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.086906835608134989, 0.0, 0.0,
> 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 4
>  stamp:
>    secs: 1283264216
>    nsecs: 579240571
>  frame_id: map
> pose:
>  pose:
>    position:
>      x: 0.675671959326
>      y: 0.0277861157726
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.012026257738
>      w: 0.999927681947
>  covariance: [0.36283060340373735, 0.014118143333576845, 0.0, 0.0, 0.0,
> 0.0, 0.014118143333576845, 0.30805645206476079, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.099034657680711305, 0.0, 0.0,
> 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 5
>  stamp:
>    secs: 1283264217
>    nsecs: 219611415
>  frame_id: map
> pose:
>  pose:
>    position:
>      x: 0.843883973475
>      y: 0.047129095818
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.0122639546581
>      w: 0.99992479488
>  covariance: [0.39540569106077028, 0.0092167690246466108, 0.0, 0.0, 0.0,
> 0.0, 0.0092167690246466108, 0.36344868131336877, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11715264662452711, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> =========================
> TOPIC /odom:
> header:
>  seq: 1945
>  stamp:
>    secs: 1283264186
>    nsecs: 134936757
>  frame_id: odom
> child_frame_id: ''
> pose:
>  pose:
>    position:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>      z: 0.0
>       w: 1.0
>  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> twist:
>  twist:
>    linear:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>     angular:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>   covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 1946
>  stamp:
>    secs: 1283264186
>    nsecs: 234943671
>  frame_id: odom
> child_frame_id: ''
> pose:
>  pose:
>    position:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>      z: 0.0
>       w: 1.0
>  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> twist:
>  twist:
>    linear:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>     angular:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>   covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 1947
>  stamp:
>    secs: 1283264186
>    nsecs: 334954766
>  frame_id: odom
> child_frame_id: ''
> pose:
>  pose:
>    position:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>      z: 0.0
>       w: 1.0
>  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> twist:
>  twist:
>    linear:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>     angular:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>   covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
>   .
>   .
>   .
> header:
>  seq: 2365
>  stamp:
>    secs: 1283264228
>    nsecs: 150935090
>  frame_id: odom
> child_frame_id: ''
> pose:
>  pose:
>    position:
>      x: 1151.0
>      y: -1.0
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -4.96052408606e-16
>      w: 1.0
>  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> twist:
>  twist:
>    linear:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>     angular:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>   covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 2366
>  stamp:
>    secs: 1283264228
>    nsecs: 250972872
>  frame_id: odom
> child_frame_id: ''
> pose:
>  pose:
>    position:
>      x: 1151.0
>      y: -1.0
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -4.96052408606e-16
>      w: 1.0
>  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> twist:
>  twist:
>    linear:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>     angular:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>   covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 2367
>  stamp:
>    secs: 1283264228
>    nsecs: 350933752
>  frame_id: odom
> child_frame_id: ''
> pose:
>  pose:
>    position:
>      x: 1151.0
>      y: -1.0
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -4.96052408606e-16
>      w: 1.0
>  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> twist:
>  twist:
>    linear:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>     angular:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>   covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 2368
>  stamp:
>    secs: 1283264228
>    nsecs: 452759196
>  frame_id: odom
> child_frame_id: ''
> pose:
>  pose:
>    position:
>      x: 1151.0
>      y: -1.0
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -4.96052408606e-16
>      w: 1.0
>  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> twist:
>  twist:
>    linear:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>     angular:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>   covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> ---
> header:
>  seq: 2369
>  stamp:
>    secs: 1283264228
>    nsecs: 551957980
>  frame_id: odom
> child_frame_id: ''
> pose:
>  pose:
>    position:
>      x: 1151.0
>      y: -1.0
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -4.96052408606e-16
>      w: 1.0
>  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
> twist:
>  twist:
>    linear:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>     angular:
>       x: 0.0
>      y: 0.0
>      z: 0.0
>   covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
> 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
>
> ===============================
> TOPIC /particleclouds
> header:
>  seq: 2
>  stamp:
>    secs: 1283264215
>    nsecs: 756479577
>  frame_id: map
> poses:
>  -
>    position:
>      x: 0.276259489987
>      y: 0.59703817945
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.149056594966
>      w: 0.988828666401
>  -
>    position:
>      x: 0.740718253068
>      y: -0.089673382954
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.136820644404
>      w: 0.990595836487
>  -
>    position:
>      x: -0.235402031999
>      y: -0.640814719739
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.0373773127287
>      w: 0.999301224103
>  -
>    position:
>      x: 0.195227750385
>      y: -0.533825584407
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.253166567161
>      w: 0.967422704546
>  -
>    position:
>      x: 1.06535852562
>      y: -0.111224649481
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.134672195018
>      w: 0.990890205769
>  -
>    position:
>      x: 0.509493294264
>      y: 0.382609565205
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.200947384627
>      w: 0.979602035835
>  -
>    position:
>      x: 0.106648801578
>      y: -0.0610606053734
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.261785029675
>      w: 0.965126208451
>  -
>    position:
>      x: 0.738234944648
>      y: 0.278477991024
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.0384439240972
>      w: 0.999260759111
>  -
>    position:
>      x: -0.297492221037
>      y: 0.558259590591
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.30049924452
>      w: 0.953782052695
>  -
>    position:
>      x: 0.0593276507712
>      y: 0.492263601603
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.181497946659
>      w: 0.983391323614
>  -
>    position:
>      x: 0.532087494476
>      y: 0.0744991931483
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.0384564241622
>      w: 0.999260278126
>  -
>    position:
>      x: 0.143513019496
>      y: -0.954441759189
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.182208088273
>      w: 0.983259992356
>  -
>    position:
>      x: 0.203350320118
>      y: 0.357348693277
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.131358876168
>      w: 0.99133488068
>  -
>    position:
>      x: -0.248090219989
>      y: 0.0224983919907
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.0394652395713
>      w: 0.999220943969
>  -
>    position:
>      x: 0.961917733019
>      y: 0.617788587923
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.150467678296
>      w: 0.988614928973
>      .
>      .
>      .
>    position:
>      x: 0.386256567908
>      y: -0.578717321836
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.026541595927
>      w: 0.999647709789
>  -
>    position:
>      x: 0.261445201574
>      y: 0.933399436686
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.29194663018
>      w: 0.956434611004
>  -
>    position:
>      x: 1.10912564935
>      y: 0.88026309372
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.231161506464
>      w: 0.972915390941
>  -
>    position:
>      x: 0.436744885215
>      y: -0.129462255606
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.0893570920922
>      w: 0.995999653661
>  -
>    position:
>      x: 2.40085931845
>      y: 0.0586482542803
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.153628940656
>      w: 0.988128609338
>  -
>    position:
>      x: 0.552989709579
>      y: -0.824151892873
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.229310627028
>      w: 0.973353294715
>  -
>    position:
>      x: 0.595353605949
>      y: 0.225873002097
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: 0.179521736015
>      w: 0.983754007005
>  -
>    position:
>      x: -0.335761130772
>      y: -0.438287725821
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.223219289279
>      w: 0.974768253942
>  -
>    position:
>      x: 1.5799615211
>      y: -0.0490837249542
>       z: 0.0
>    orientation:
>      x: 0.0
>      y: 0.0
>       z: -0.200542106019
>      w: 0.97968508395
> ==================
> TOPIC /scan
> ---
> header:
>  seq: 859
>  stamp:
>    secs: 1283264192
>    nsecs: 891810522
>  frame_id: laser
> angle_min: -1.57079637051
> angle_max: 1.57079637051
> angle_increment: 0.00872664619237
> time_increment: 7.40740724723e-05
> scan_time: 0.0266666673124
> range_min: 0.0
> range_max: 8.10000038147
> ranges: [5.3940000534057617, 5.4010000228881836, 5.4110002517700195,
> 5.4130001068115234, 5.4150004386901855, 5.4150004386901855,
> 5.5810003280639648, 6.0370001792907715, 7.9800004959106445,
> 7.7320003509521484, 6.1870002746582031, 6.1580004692077637,
> 6.1830000877380371, 7.8010005950927734, 7.8070001602172852,
> 7.820000171661377, 7.8320002555847168, 7.9100003242492676,
> 7.6790003776550293, 7.5970005989074707, 7.3090004920959473,
> 7.0900001525878906, 7.1090002059936523, 7.1180005073547363,
> 7.13800048828125, 7.1570005416870117, 7.1760001182556152,
> 4.264000415802002,
> 4.2770004272460938, 4.75, 8.2639999389648438, 32.76300048828125,
> 32.76300048828125, 4.0260000228881836, 5.7460002899169922,
> 7.764000415802002, 4.6400003433227539, 5.0400004386901855,
> 3.9720001220703125, 4.2760000228881836, 4.2410001754760742,
> 4.1750001907348633, 4.139000415802002, 4.1110000610351562,
> 3.8270001411437988, 3.944000244140625, 4.0610003471374512,
> 3.8340001106262207, 3.6180002689361572, 4.0470004081726074,
> .
> .
> .
> .
> .
> header:
>  seq: 1061
>  stamp:
>    secs: 1283264236
>    nsecs: 965322
>  frame_id: laser
> angle_min: -1.57079637051
> angle_max: 1.57079637051
> angle_increment: 0.00872664619237
> time_increment: 7.40740724723e-05
> scan_time: 0.0266666673124
> range_min: 0.0
> range_max: 8.10000038147
> ranges: [4.5940003395080566, 4.5980000495910645, 3.7400002479553223,
> 3.7380001544952393, 3.7190001010894775, 4.0370001792907715,
> 3.4580001831054688, 3.567000150680542, 3.2970001697540283,
> 3.3000001907348633, 3.3880002498626709, 3.1510002613067627,
> 2.9940001964569092, 3.1760001182556152, 3.7020001411437988,
> 3.694000244140625, 3.0930001735687256, 2.8700001239776611,
> 3.2510001659393311, 3.5540001392364502, 3.4530000686645508,
> 3.2610001564025879, 2.944000244140625, 2.812000036239624,
> 2.6570000648498535, 2.6560001373291016, 2.9130001068115234,
> 3.569000244140625, 3.1160001754760742, 3.1190001964569092,
> 3.5170001983642578, 8.5329999923706055, 8.5580005645751953,
> 3.3710000514984131, 3.3940000534057617, 8.6350002288818359,
> 3.1750001907348633, 3.0980000495910645, 3.1060001850128174,
> 8.8610000610351562, 8.8900003433227539, 8.9200000762939453,
> 8.9590005874633789, 8.9880008697509766, 9.0200004577636719,
> 9.0580005645751953, 9.0989999771118164, 9.1400003433227539,
> 9.0700006484985352, 9.1160001754760742, 9.1530008316040039,
> 9.2000007629394531, 9.2370004653930664, 9.2920007705688477,
> 9.3360004425048828, 9.3819999694824219, 9.4270000457763672,
> 8.0729999542236328, 7.9720005989074707, 7.8580002784729004,
> 7.758000373840332, 7.6540002822875977, 32.767002105712891,
> 32.76300048828125, 32.76300048828125, 32.76300048828125,
> 7.0290002822875977,
> 7.0770001411437988, 6.9890003204345703, 6.9090003967285156,
> 6.8310003280639648, 6.7570004463195801, 6.6820001602172852,
> 6.6010003089904785, 6.5210003852844238, 5.6670002937316895,
> 5.629000186920166, 3.7200002670288086, 3.6830000877380371,
> 3.6550002098083496, 3.6260001659393311, 3.5970001220703125,
> 3.6040000915527344, 3.570000171661377, 3.5400002002716064,
> 3.5130002498626709, 3.4760000705718994, 3.4490001201629639,
> 3.4230000972747803, 3.3880002498626709, 3.3670001029968262,
> 3.3310000896453857, 3.315000057220459, 3.2970001697540283,
> 3.2670001983642578, 3.2460000514984131, 3.2200002670288086,
> 3.2000000476837158, 3.1810002326965332, 3.1620001792907715,
> 3.1360001564025879, 3.1120002269744873, 3.0990002155303955,
> 3.0260002613067627, 3.0230002403259277, 2.9980001449584961,
> 2.9810001850128174, 2.9600000381469727, 2.9880001544952393,
> 2.9690001010894775, 2.9470000267028809, 2.9350001811981201,
> 2.9210002422332764, 2.9010000228881836, 2.8910000324249268,
> 2.8730001449584961, 2.8670001029968262, 2.8490002155303955,
> 2.8340001106262207, 2.8010001182556152, 2.7010002136230469,
> 2.7920000553131104, 2.7820000648498535, 2.7650001049041748,
> 2.4220001697540283, 1.7670000791549683, 1.7690000534057617,
> 1.8730001449584961, 2.2690000534057617, 2.255000114440918,
> 2.2880001068115234, 2.2760000228881836, 2.2740001678466797,
> 2.2800002098083496, 2.2950000762939453, 2.3289999961853027,
> 2.4840002059936523, 2.4740002155303955, 2.4740002155303955,
> 2.4610002040863037, 2.442000150680542, 2.4330000877380371,
> 2.4230000972747803, 2.4230000972747803, 2.4140000343322754,
> 2.4040000438690186, 2.062000036239624, 2.0530002117156982,
> 2.0460000038146973, 2.0370001792907715, 2.0360000133514404,
> 2.0190000534057617, 1.6360000371932983, 1.6550000905990601,
> 1.9040000438690186, 2.0150001049041748, 2.0150001049041748,
> 2.0170001983642578, 2.0170001983642578, 2.0170001983642578,
> 2.0180001258850098, 2.0190000534057617, 2.0220000743865967, 2.125,
> 2.3340001106262207, 2.3380000591278076, 2.3390002250671387,
> 2.3390002250671387, 2.3300001621246338, 2.3310000896453857,
> 2.3310000896453857, 2.3320000171661377, 2.3320000171661377,
> 2.3320000171661377, 2.3320000171661377, 2.3320000171661377,
> 2.3300001621246338, 2.2870001792907715, 2.2760000228881836,
> 2.2710001468658447, 2.2510001659393311, 2.0610001087188721,
> 2.128000020980835, 2.2840001583099365, 1.9290001392364502,
> 1.9240001440048218, 1.9050000905990601, 1.9030001163482666,
> 1.91100013256073, 1.91100013256073, 1.9190001487731934, 1.9180001020431519,
> 1.9190001487731934, 1.9180001020431519, 1.9260001182556152,
> 1.9260001182556152, 1.9350000619888306, 1.9350000619888306,
> 1.9350000619888306, 1.9350000619888306, 1.942000150680542,
> 1.9410001039505005, 1.9510000944137573, 1.9520001411437988,
> 1.9610000848770142, 1.970000147819519, 1.970000147819519,
> 1.9790000915527344, 1.9790000915527344, 1.9780000448226929,
> 1.9880000352859497, 1.9950001239776611, 2.004000186920166,
> 2.005000114440918, 2.0140001773834229, 2.0230000019073486,
> 2.0310001373291016, 2.0310001373291016, 2.0390000343322754,
> 2.0470001697540283, 2.1840000152587891, 2.5300002098083496,
> 2.5400002002716064, 2.5480000972747803, 2.5580000877380371,
> 2.567000150680542, 2.5770001411437988, 2.5840001106262207,
> 2.6040000915527344, 2.6030001640319824, 2.6220002174377441,
> 2.632000207901001, 2.6400001049041748, 2.6500000953674316,
> 2.6680002212524414, 2.6780002117156982, 2.630000114440918,
> 2.5890002250671387, 2.562000036239624, 2.5250000953674316,
> 2.4870002269744873, 2.4500000476837158, 2.4240000247955322,
> 2.3960001468658447, 2.3580000400543213, 2.3370001316070557,
> 2.3500001430511475, 2.5960001945495605, 2.6060001850128174,
> 2.5900001525878906, 2.6010000705718994, 2.627000093460083,
> 2.6350002288818359, 2.6390001773834229, 2.6550002098083496,
> 2.6720001697540283, 2.6850001811981201, 2.7030000686645508,
> 2.7200000286102295, 2.7370002269744873, 2.7460000514984131,
> 2.8300001621246338, 2.8270001411437988, 2.8020000457763672,
> 2.7840001583099365, 2.7410001754760742, 2.753000020980835,
> 2.7140002250671387, 2.7310001850128174, 2.7590000629425049,
> 2.7850000858306885, 2.8030002117156982, 2.8370001316070557,
> 2.8630001544952393, 2.8880002498626709, 2.9140000343322754,
> 2.9480001926422119, 2.9760000705718994, 3.0130002498626709,
> 1.9100000858306885, 1.9040000438690186, 2.0280001163482666,
> 3.1670000553131104, 3.9000000953674316, 3.8720002174377441,
> 3.8550002574920654, 2.0230000019073486, 2.0450000762939453,
> 2.0559999942779541, 2.062000036239624, 2.0410001277923584,
> 2.0350000858306885, 1.0120000839233398, 0.99700003862380981,
> 0.98600006103515625, 0.99400001764297485, 1.0120000839233398,
> 3.8570001125335693, 3.9100000858306885, 0.99700003862380981,
> 4.0320000648498535, 4.1070003509521484, 4.1720004081726074,
> 5.4050002098083496, 5.3780002593994141, 5.4800004959106445,
> 5.5710000991821289, 5.6830000877380371, 5.6350002288818359,
> 5.6160001754760742, 5.5890002250671387, 5.5710000991821289,
> 5.5530004501342773, 5.5340003967285156, 5.5270004272460938,
> 5.499000072479248, 5.5110001564025879, 5.6480002403259277,
> 5.8010001182556152, 5.948000431060791, 6.1160001754760742,
> 6.444000244140625, 6.6750001907348633, 6.883000373840332,
> 7.008000373840332,
> 7.0220003128051758, 7.0030002593994141, 6.9860005378723145,
> 6.9670004844665527, 6.5100002288818359, 6.9220004081726074,
> 6.8930001258850098, 6.8950004577636719, 6.8860001564025879,
> 6.8590002059936523, 6.6260004043579102, 6.6170001029968262,
> 6.6080002784729004, 6.6080002784729004, 6.5970001220703125,
> 6.5890002250671387, 6.5720005035400391, 6.5630002021789551,
> 6.8060002326965332, 6.8060002326965332, 6.7960004806518555,
> 6.7860002517700195, 6.3570003509521484, 6.7680001258850098,
> 6.7660002708435059, 6.7560005187988281, 6.754000186920166,
> 4.8280000686645508, 4.7670001983642578, 4.9860000610351562,
> 4.754000186920166, 32.76300048828125, 4.8530001640319824,
> 5.4320001602172852, 6.7350001335144043, 6.7470002174377441]
> intensities: []
>
>
> Do you see anything problematic for localization?
> Because I think localization is problematic that's why next step move_base
> for path_planning does not work.
> I am sorry that you had to read such a long message.
> Please any idea?
>
> with best regards,
> safdar
>
> --
> View this message in context:
> http://ros-users.122217.n3.nabble.com/sensor-origin-tp1388170p1394818.html
> Sent from the ROS-Users mailing list archive at Nabble.com.
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100831/24673e5d/attachment-0003.html>


More information about the ros-users mailing list