jkulhanek / robot-visual-navigation

Visual Navigation in Real-World Indoor Environments Using End-to-End Deep Reinforcement Learning Official Implementation
MIT License
58 stars 11 forks source link

real robot issues #26

Open jiacheng-yao123 opened 8 months ago

jiacheng-yao123 commented 8 months ago

I am a graduate student and very interested in your research on visual navigation. Recently, I've been having some problems reproducing the results of the real turtlebot2. I ran into some issues when running the code using the kinect1 camera and would really like your guidance and help.

Run the following commands roslaunch robot_controller start.launch

python src/ros_agent_service/src/main.py

python goal_picker/src/setgoal.py --image /home/zwz/robot-visual-navigation-master/goal/door.jpg The following error was encountered:

[ERROR] [1704981429.247813]: bad callback: <function create_send_response.<locals>.send_response at 0x7f0fe4461040>
Traceback (most recent call last):
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
    cb(msg)
  File "ros_agent_service/src/main.py", line 33, in send_response
    action = server.compute_step(request)
  File "ros_agent_service/src/main.py", line 22, in compute_step
    action = self.agent.act((observation, goal,))
  File "/home/zwz/robot-visual-navigation-master/ros/src/ros_agent_service/src/agent.py", line 57, in act
    obs = (_transform_image(img), _transform_image(goal))
  File "/home/zwz/robot-visual-navigation-master/ros/src/ros_agent_service/src/agent.py", line 13, in _transform_image
    return np.expand_dims(((img.astype(np.float32) - mean) / std).transpose([2, 0, 1]), 0)
ValueError: axes don't match array
img.shape (84, 84) [[ 46  51  47 ... 110 107 108]
 [ 53  52  26 ... 125  98 106]
 [ 58  42  46 ... 124 117 116]
 ...
 [101  95  98 ... 128 129 128]
 [ 96 106  86 ... 123 129 126]
 [ 91  95  72 ... 123 129 125]]
goal.shape (84, 84, 3) [[[139 158 154]
  [139 158 154]
  [144 162 161]
  ...
  [150 170 169]
  [147 167 166]
  [145 165 166]]

 [[139 158 154]
  [141 160 156]
  [144 162 161]
  ...
  [152 170 172]
  [149 167 169]
  [147 165 165]]

 [[139 158 154]
  [142 161 157]
  [143 162 160]
  ...
  [155 170 176]
  [152 167 170]
  [149 165 163]]

According to the printout, the goal image is a 3-channel RGB image and the observation image is a single-channel grayscale image. I found the gmapping_demo.launch and 3dsensor.launch for starting the sensor based on the command roslaunch robot_controller start.launch how to start the RGB image in these two files, and what should I change in the specific code, looking forward to your reply.

gmapping_demo.launch

<launch>
  <!-- 3D sensor -->
  <arg name="3d_sensor" default="$(env TURTLEBOT_3D_SENSOR)"/>  <!-- r200, kinect, asus_xtion_pro -->
  <include file="$(find turtlebot_bringup)/launch/3dsensor.launch">
    <arg name="rgb_processing" value="false" />
    <arg name="depth_registration" value="false" />
    <arg name="depth_processing" value="false" />

    <!-- We must specify an absolute topic name because if not it will be prefixed by "$(arg camera)".
         Probably is a bug in the nodelet manager: https://github.com/ros/nodelet_core/issues/7 --> 
    <arg name="scan_topic" value="/scan" />
  </include>

  <!-- Gmapping -->
  <arg name="custom_gmapping_launch_file" default="$(find turtlebot_navigation)/launch/includes/gmapping/$(arg 3d_sensor)_gmapping.launch.xml"/>
  <include file="$(arg custom_gmapping_launch_file)"/>

  <!-- Move base -->
  <include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml"/>

</launch>

3dsensor.launch

<!-- 
  Turtlebot is a bit low on horsepower...

  We use openni_camera here, turn everything on by default
  (allows the user to conveniently see everything when
  launching this on its own - use with 
  turtebot_rviz_launchers/view_robot.launch to visualise)
  and provide args to disable them so you can optimise the
  horsepower for your application.

  For an example of disabling processing modules, check
  any of the turtlebot_rapps (e.g. android_make_a_map.launch
  only enables scan_processing for depthimage_to_laserscan and
  rgb_processing for the android tele-view).
-->
<launch>
  <!-- "camera" should uniquely identify the device. All topics are pushed down
       into the "camera" namespace, and it is prepended to tf frame ids. -->
  <arg name="camera"      default="camera"/>
  <arg name="publish_tf"  default="false"/>
  <arg name="3d_sensor"   default="$(env TURTLEBOT_3D_SENSOR)"/>  <!-- kinect, asus_xtion_pro -->

  <!-- Factory-calibrated depth registration -->
  <arg name="depth_registration"              default="true"/>
  <arg     if="$(arg depth_registration)" name="depth" value="depth_registered" />
  <arg unless="$(arg depth_registration)" name="depth" value="depth" />

  <!-- Processing Modules -->
  <arg name="rgb_processing"                  default="true"/>
  <arg name="ir_processing"                   default="true"/>
  <arg name="depth_processing"                default="true"/>
  <arg name="depth_registered_processing"     default="true"/>
  <arg name="disparity_processing"            default="true"/>
  <arg name="disparity_registered_processing" default="true"/>
  <arg name="scan_processing"                 default="true"/>

  <!-- Worker threads for the nodelet manager -->
  <arg name="num_worker_threads" default="4" />

  <!-- Laserscan topic -->
  <arg name="scan_topic" default="scan"/>

  <include file="$(find turtlebot_bringup)/launch/includes/3dsensor/$(arg 3d_sensor).launch.xml">
    <arg name="camera"                          value="$(arg camera)"/>
    <arg name="publish_tf"                      value="$(arg publish_tf)"/>
    <arg name="depth_registration"              value="$(arg depth_registration)"/>
    <arg name="num_worker_threads"              value="$(arg num_worker_threads)" />

    <!-- Processing Modules -->
    <arg name="rgb_processing"                  value="$(arg rgb_processing)"/>
    <arg name="ir_processing"                   value="$(arg ir_processing)"/>
    <arg name="depth_processing"                value="$(arg depth_processing)"/>
    <arg name="depth_registered_processing"     value="$(arg depth_registered_processing)"/>
    <arg name="disparity_processing"            value="$(arg disparity_processing)"/>
    <arg name="disparity_registered_processing" value="$(arg disparity_registered_processing)"/>
  </include>

   <!--                        Laserscan 
     This uses lazy subscribing, so will not activate until scan is requested.
   -->
  <group if="$(arg scan_processing)">
    <node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan" args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet $(arg camera)/$(arg camera)_nodelet_manager">
      <!-- Pixel rows to use to generate the laserscan. For each column, the scan will
           return the minimum value for those pixels centered vertically in the image. -->
      <param name="scan_height" value="10"/>
      <param name="output_frame_id" value="$(arg camera)_depth_frame"/>
      <param name="range_min" value="0.45"/>
      <remap from="image" to="$(arg camera)/$(arg depth)/image_raw"/>
      <remap from="scan" to="$(arg scan_topic)"/>

      <!-- Somehow topics here get prefixed by "$(arg camera)" when not inside an app namespace,
           so in this case "$(arg scan_topic)" must provide an absolute topic name (issue #88).
           Probably is a bug in the nodelet manager: https://github.com/ros/nodelet_core/issues/7 -->
      <remap from="$(arg camera)/image" to="$(arg camera)/$(arg depth)/image_raw"/>
      <remap from="$(arg camera)/scan" to="$(arg scan_topic)"/>
    </node>
  </group>
</launch>