nfaction / ua-ros-pkg-nfaction

Automatically exported from code.google.com/p/ua-ros-pkg
0 stars 0 forks source link

Issue about tilting laser #23

Closed GoogleCodeExporter closed 9 years ago

GoogleCodeExporter commented 9 years ago
What steps will reproduce the problem?
1.I have AX12+ motor and Hokuyo UHG laser at hand, now am following the 
ua-ros-pkg for laser tilting. The mechanism can work, but I also experienced 
such issues:

2. In file ua_controllers/wubble_actions/nodes/hokuyo_laser_action.py, when 
ERROR_THRESHOLD=0.01, the motor sometimes will stop with actual error=0.015xx; 
if ERROR_THRESHOLD sets to 0.02,motor running is non-stop, no matter what 
joint_speed is in laser_tilt.yaml. Then what are the adjustments I can use to 
achieve ERROR_THRESHOLD 0.01? 

3.Line 63 of the file 
ua_controllers/wubble_actions/nodes/hokuyo_laser_action.py, the message type of 
topic_tilt_controller/state should not be JointControllerState but JointState

What is the expected output? What do you see instead?

What version of the product are you using? On what operating system?
Ubuntu 10.04, ROS cturtle

Please provide any additional information below.

Original issue reported on code.google.com by Wu.Xiao...@gmail.com on 5 Oct 2010 at 1:26

GoogleCodeExporter commented 9 years ago
Hi,

For #2, the error threshold is specified in radians, so 0.01 radians is 0.57 
degrees and 0.015 radians is 0.86 degrees, where the difference between the two 
is 0.29 degrees which is lower than the encoder resolution of AX-12+ (which is 
~0.35 degrees). So I don't think we can do better than that since it's an 
encoder resolution limit of the motor.

I didn't see any difference when setting the threshold value to 0.02, the motor 
was stopping properly. The problem might be that your motor state update rate 
is too low, try setting it to something higher, say 10 or 15Hz. You can do that 
when you launch the ax12 controller manager, just modify the update_rate 
parameter.

<node name="ttyUSB0_manager" pkg="ax12_controller_core" 
type="controller_manager.py" required="true" output="screen">
    <param name="port_name" type="str" value="/dev/ttyUSB0"/>
    <param name="baud_rate" type="int" value="1000000"/>
    <param name="max_motor_id" type="int" value="25"/>
    <param name="update_rate" type="int" value="15"/>
</node>

As for #3, that would be true if we only used this code to communicate with 
real hardware, but we also use that same code in simulation. There we reuse 
PR2's simulated actuators and hence laser_tilt_controller/state topic is of 
type pr2_controllers_msgs.JointControllerState. What we do here is the 
following:

1. we have a node that subscribes to actual hardware state and republishes this 
info in PR2 JointControllerState format. Look at ax12_to_pr2_state_msgs.py node 
in wubble_controllers package.

2. Then we simply remap the subscribed topic in action server, like so:

<node name="tilt_action" pkg="wubble_actions" type="hokuyo_laser_action.py" 
output="screen">
    <remap from="/laser_tilt_controller/state" to="/laser_tilt_controller/state_pr2_msgs"/>
</node>

Let me know if anything is unclear or you have other questions.

Original comment by areb...@gmail.com on 5 Oct 2010 at 10:38

GoogleCodeExporter commented 9 years ago
Hi, arebgun,

thanks for your detailed explanation.

For the issue of ERROR_THRESHOLD, the motor runs smoothly when set to 0.02, and 
I am fine with it.
I also understand the remapping mechanism from state to state_pr2_message 

There is another problem I am still struggling with, 
with the tilting mechanism, I would make collision-map from laser data. 
Following ROS tutorial @ 
http://www.ros.org/wiki/motion_planning_environment/Tutorials/Making%20collision
%20maps%20from%20self-filtered%20tilting%20laser%20data,

I added loading commands for filter, assembler and snapshotter in launch file, 
and also published a tf between base_link and tilt_laser. Finally in rviz, I 
can observe results up to the step of assembler, but nothing for snapshotter. 
After checking ROS wiki document, it seems a message called 
pr2_msgs/LaserScannerSignal
is necessary for snapshotter to be triggered, but up to now is missing in the 
laser_tilt_controller.
So my question is, how would you advise to handle it? By diverting to and 
calling corresponding pr2 modules, or manually generate the required  
LaserScannerSignal msg?

Original comment by Wu.Xiao...@gmail.com on 6 Oct 2010 at 2:04

GoogleCodeExporter commented 9 years ago
Just some updates for the problem described in my previous thread.
I published the pr2_msgs/LaserScannerSignal message in hokuyo_laser_action.py, 
i.e., set LaserScannerSignal.signal to 0 or 1 when the joint sweeps to bottom 
or up edge,  and that seems working, the point clouds looks fine.

Original comment by Wu.Xiao...@gmail.com on 7 Oct 2010 at 6:53

GoogleCodeExporter commented 9 years ago
Ah, good to hear that it's working now. I will add that stuff to our version of 
the laser action in the next day or two.

Original comment by areb...@gmail.com on 8 Oct 2010 at 1:29

GoogleCodeExporter commented 9 years ago

Original comment by areb...@gmail.com on 8 Oct 2010 at 10:44