|
From: <mee...@us...> - 2009-08-19 17:06:34
|
Revision: 22281
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=22281&view=rev
Author: meeussen
Date: 2009-08-19 17:06:24 +0000 (Wed, 19 Aug 2009)
Log Message:
-----------
tested version of robot_pose_ekf after many message changes
Modified Paths:
--------------
pkg/trunk/demos/milestone2/milestone2_actions/milestone2.launch
pkg/trunk/stacks/navigation/robot_pose_ekf/robot_pose_ekf.launch
pkg/trunk/stacks/navigation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/stacks/pr2/pr2_alpha/teleop_controllers.launch
Modified: pkg/trunk/demos/milestone2/milestone2_actions/milestone2.launch
===================================================================
--- pkg/trunk/demos/milestone2/milestone2_actions/milestone2.launch 2009-08-19 16:30:43 UTC (rev 22280)
+++ pkg/trunk/demos/milestone2/milestone2_actions/milestone2.launch 2009-08-19 17:06:24 UTC (rev 22281)
@@ -51,18 +51,9 @@
<!-- Robot pose ekf -->
-<node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" machine="four">
- <param name="freq" value="30.0"/>
- <param name="sensor_timeout" value="1.0"/>
- <param name="publish_tf" value="true"/>
- <param name="odom_used" value="true"/>
- <param name="imu_used" value="true"/>
- <param name="vo_used" value="false"/>
- <remap from="odom" to="pr2_base_odometry/odom"/>
-</node>
+ <include file="$(find robot_pose_ekf)/robot_pose_ekf.launch" />
-
<!-- Sends robot pose when robot moves for irosweb interface -->
<node pkg="tf" machine="two" type="change_notifier"/>
Modified: pkg/trunk/stacks/navigation/robot_pose_ekf/robot_pose_ekf.launch
===================================================================
--- pkg/trunk/stacks/navigation/robot_pose_ekf/robot_pose_ekf.launch 2009-08-19 16:30:43 UTC (rev 22280)
+++ pkg/trunk/stacks/navigation/robot_pose_ekf/robot_pose_ekf.launch 2009-08-19 17:06:24 UTC (rev 22281)
@@ -5,8 +5,8 @@
<param name="sensor_timeout" value="1.0"/>
<param name="publish_tf" value="true"/>
<param name="odom_used" value="true"/>
- <param name="imu_used" value="false"/>
- <param name="vo_used" value="false"/>
+ <param name="imu_used" value="true"/>
+ <param name="vo_used" value="true"/>
<remap from="odom" to="/pr2_base_odometry/odom" />
</node>
Modified: pkg/trunk/stacks/navigation/robot_pose_ekf/src/odom_estimation_node.cpp
===================================================================
--- pkg/trunk/stacks/navigation/robot_pose_ekf/src/odom_estimation_node.cpp 2009-08-19 16:30:43 UTC (rev 22280)
+++ pkg/trunk/stacks/navigation/robot_pose_ekf/src/odom_estimation_node.cpp 2009-08-19 17:06:24 UTC (rev 22281)
@@ -270,8 +270,8 @@
#ifdef __EKF_DEBUG_FILE__
// write to file
double Rx, Ry, Rz;
- vo_meas_base.getBasis().getEulerZYX(Rz, Ry, Rx);
- vo_file_ << vo_meas_base.getOrigin().x() << " " << vo_meas_base.getOrigin().y() << " " << vo_meas_base.getOrigin().z() << " "
+ vo_meas_.getBasis().getEulerZYX(Rz, Ry, Rx);
+ vo_file_ << vo_meas_.getOrigin().x() << " " << vo_meas_.getOrigin().y() << " " << vo_meas_.getOrigin().z() << " "
<< Rx << " " << Ry << " " << Rz << endl;
#endif
};
Modified: pkg/trunk/stacks/pr2/pr2_alpha/teleop_controllers.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/teleop_controllers.launch 2009-08-19 16:30:43 UTC (rev 22280)
+++ pkg/trunk/stacks/pr2/pr2_alpha/teleop_controllers.launch 2009-08-19 17:06:24 UTC (rev 22281)
@@ -3,8 +3,8 @@
reuse in teleop_joystick, teleop_ps3 -->
<rosparam file="$(find pr2_default_controllers)/pr2_base_controller.yaml" command="load" ns="pr2_base_controller" />
- <rosparam file="$(find pr2_default_controllers)/pr2_odometry.yaml" command="load" ns="pr2_odometry" />
- <node pkg="mechanism_control" type="spawner.py" args="pr2_base_controller pr2_odometry" output="screen"/>
+ <rosparam file="$(find pr2_default_controllers)/pr2_odometry.yaml" command="load" ns="pr2_base_odometry" />
+ <node pkg="mechanism_control" type="spawner.py" args="pr2_base_controller pr2_base_odometry" output="screen"/>
<rosparam file="$(find pr2_default_controllers)/pr2_joint_velocity_controllers.yaml" command="load" />
<node pkg="mechanism_control" type="spawner.py" args="torso_lift_velocity_controller" output="screen" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|