adds fabs() to test in commande

This commit is contained in:
Louis-Guillaume DUBOIS 2015-05-07 23:59:49 +02:00
parent 26bfafc9c9
commit bf2bcb56b5
3 changed files with 27 additions and 7 deletions

View file

@ -1,5 +0,0 @@
<launch>
<node name="commande" pkg="hand_control" type="commande">
<remap from="/filtre/output" to="/cmd_vel"/>
</node>
</launch>

View file

@ -0,0 +1,25 @@
<launch>
<node name="filtre_z" pkg="hand_control" type="filtre">
<remap from="/filtre/input" to="/random_pcl"/>
</node>
<param name="/publisher/freq" value="30.0" type="double" />
<param name="/publisher/length" value="50" type="int" />
<node name="publisher" pkg="hand_control" type="random_pcl_publisher" >
<remap from="/random/output" to="/random_pcl"/>
</node>
<node name="estimator" pkg="hand_control" type="normal_estimator">
<remap from="/estimator/input" to="/filtre/output"/>
</node>
<param name="/commande/min_number" value="5" type="int"/>
<param name="/commande/x_dev_min" value="0." type="double"/>
<param name="/commande/y_dev_min" value="0." type="double"/>
<param name="/commande/dz_dev_min" value="0." type="double"/>
<node name="commande" pkg="hand_control" type="commande">
<remap from="/commande/input" to="/estimator/output"/>
</node>
</launch>

View file

@ -42,12 +42,12 @@ class Run
mvt->linear.z = dz * z_vel;
ROS_INFO("z changed");
}
if (xx > x_dev_min)
if (fabs(xx) > x_dev_min)
{
mvt->linear.y = xx * plan_vel;
// because of the kinect orientation
}
if (yy > y_dev_min)
if (fabs(yy) > y_dev_min)
{
mvt->linear.x = yy * plan_vel;
// because of the kinect orientation