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

Revision history [back]

click to hide/show revision 1
initial version

Actually, the environment server is perfectly happy to accept an empty collision map. If you build and start up this executable you should see that the environment server starts up:

#include <ros/ros.h>
#include <arm_navigation_msgs/CollisionMap.h>

int main(int argc, char** argv)
{
  ros::init(argc, argv, "empty_collision_map_publisher");
  //figuring out whether robot_description has been remapped

  ros::NodeHandle nh;

  ros::Publisher pub = nh.advertise<arm_navigation_msgs::CollisionMap>("/collision_map_occ", 1, true);

  while(ros::ok()) {
    arm_navigation_msgs::CollisionMap coll;
    coll.header.frame_id = "odom_combined";
    coll.header.stamp = ros::Time::now();
    pub.publish(coll);
  }

  return 0;
}

The issue is that there are checks in collider.cpp to only publish if there are some occupied points (check out the first line of the publishCollisionMap function). One option is to add a parameter to collider that will cause it to publish even if there are no points - if this is acceptable I'll add it in and release arm_navigation_experimental.