Take a look at this implementation of a "virtual bumper" that does essentially what you want, but by using comparison of the odometry and pose data to detect collisions (no bump sensors needed!).
The key part of the code that populates the pointcloud is:
// place obstacle into point cloud 0.25 meters in front of robot
float val = 0.25;
memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[0].offset], &val, sizeof(float));
val = 0.0;
memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[1].offset], &val, sizeof(float));
pointcloud_.header.stamp = ros::Time::now();
pointcloud_pub_.publish(pointcloud_);
collision_pub_.publish(true);
In the above, an obstacle is placed 0.25 meters in front of the robot (when a collision occurs), and with a Y translation of zero. Note: if you have left and right bumpers, you would add +/-Y numbers for that instead of zero.
To get it to work with gmapping, you could try converting the pointcloud into a laserscan and then publish that (on the same topic as the regular scan). There are tools for this conversion such as http://wiki.ros.org/pointcloud_to_laserscan
Here's the full implementation of the virtual bumper. It's a working standalone node that you could run without modification. It assumes you have pose and odometry data from somewhere. This was tested with the navigation stack and worked fine when used to populate the costmap obstacle layer.
/*********************************************************************
*
* Software License Agreement (BSD License)
*
* Copyright (c) 2019, Rhoeby Dynamics LLC
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Rhoeby Dynamics nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
*********************************************************************/
#include "ros/ros.h"
#include "nav_msgs/Odometry.h"
#include "geometry_msgs/Twist.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include "tf/tf.h"
#include "std_msgs/Bool.h"
#include "sensor_msgs/PointCloud2.h"
class VirtualBumper
{
public:
VirtualBumper();
virtual ~VirtualBumper() {};
protected:
void odomCallback ...
(more)