ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

MoveIt! Planning Scene not subscribing to my PointCloud2 topic

asked 2020-04-03 08:57:39 -0500

cqm4061 gravatar image

I am trying to configure my robot to generate an octomap from pointcloud data. However, nothing is subscribing to my PointCloud2 topic /pcl, and I can't see the Octomap in Rviz. I never got the MoveIt! perception pipeline tutorial to work either, but I'd rather get everything working with the robot I am working with. Below is my rqt_graph, MoveIt! launch file, robot srdf file, and sensor config file.

I am getting the following warnings and errors when I launch MoveIt!, but they don't seem related to the mapping issue.

[ WARN] [1585920130.476557339]: Could not identify parent group for end-effector 'robot' 
[ WARN] [1585920130.547927589]: Kinematics solver doesnt support #attempts anymore, but only a timeout. Please remove the parameter '/rviz_racecar_vm_52748_3078963727698895796/robot/kinematics_solver_attempts' from your configuration. 
[ERROR] [1585920130.606949006]: Group 'robot' is not a chain 
[ERROR] [1585920130.607006233]: Kinematics solver of type 'kdl_kinematics_plugin/KDLKinematicsPlugin' could not be initialized for group 'robot' 
[ERROR] [1585920130.607158661]: Kinematics solver could not be instantiated for joint group robot.

rqt_graph C:\fakepath\Screen Shot 2020-04-03 at 9.23.46 AM.png

demo.launch <launch>

  <!-- Load the SRDF and other .yaml configuration files on the param server -->
  <!-- The semantic description that corresponds to the URDF -->
  <param name="robot_description_semantic" textfile="$(find racecar_moveit_config)/config/racecar.srdf" />

  <!-- Sensors Functionality -->
  <!-- Params for 3D sensors config -->
  <rosparam command="load" file="$(find racecar_moveit_config)/config/sensors_3d.yaml" />

  <!-- Params for the octomap monitor -->
  <param name="octomap_frame" type="string" value="map" />
  <param name="octomap_resolution" type="double" value="0.025" />
  <param name="max_range" type="double" value="5.0" />

  <!-- Start the actual move_group node/action server -->
  <!-- move_group settings -->
  <arg name="allow_trajectory_execution" default="false"/>
  <arg name="max_safe_path_cost" default="1"/>
  <arg name="jiggle_fraction" default="0.05" />
  <arg name="publish_monitored_planning_scene" default="true"/>
  <arg name="capabilities" default=""/>
  <arg name="disable_capabilities" default=""/>

  <node name="move_group" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen">
    <!-- Set the display variable, in case OpenGL code is used internally -->
    <env name="DISPLAY" value="$(optenv DISPLAY :0)" />

    <param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
    <param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
    <param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
    <param name="capabilities" value="$(arg capabilities)"/>
    <param name="disable_capabilities" value="$(arg disable_capabilities)"/>

    <!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->
    <param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
    <param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
    <param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
    <param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
  </node>

  <!-- Run Rviz and load the default config to see the state of the move_group node -->
  <include file="$(find racecar_moveit_config)/launch/moveit_rviz.launch">
    <arg name="rviz_config" value="$(find racecar_moveit_config)/launch/rviz_default.rviz"/>
  </include>

  <!-- Don't know if this is required but I read somewhere that it might be -->
  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/>

</launch> ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-04-28 08:03:48 -0500

askkvn gravatar image

You can do this, for

I never got the MoveIt! perception pipeline tutorial to work either

1) Start with this, git clone latest changes getting_started page

2) To run perception pipeline tutorial,

Modify obstacle_avoidance_demo.launch file as below, (By adding static transform for panda_link0 to temp_link and temp_link to camera_rgb_optical_frame solve octomap problem.)

<launch>
  <include file="$(find panda_moveit_config)/launch/demo.launch" />

  <!-- Play the rosbag that contains the pointcloud data -->
  <node pkg="moveit_tutorials" type="bag_publisher_maintain_time" name="point_clouds" />

  <!-- If needed, broadcast static tf for robot root -->

  <!-- modified static transforms solve octomap problem -->
  <node pkg="tf2_ros" type="static_transform_publisher" name="to_temp_link" args="0 -0.4 0.6 0 0 0 panda_link0 temp_link"/>
  <node pkg="tf2_ros" type="static_transform_publisher" name="to_panda_base" args="0 0 0 0.1882209 0.0680271 -1.91357652 temp_link camera_rgb_optical_frame"/>

  <!-- <node pkg="tf2_ros" type="static_transform_publisher" name="to_temp_link" args="0 0.4 -0.6 0 0 0  temp_link panda_link0" /> -->
  <!-- <node pkg="tf2_ros" type="static_transform_publisher" name="to_panda_base" args="0 0 0 0 0.2 1.92 camera_rgb_optical_frame temp_link" /> -->


</launch>
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-04-03 08:57:39 -0500

Seen: 684 times

Last updated: Apr 28 '20