diff --git a/robots/LoCoBot/locobot_control/launch/vslam_debug.launch b/robots/LoCoBot/locobot_control/launch/vslam_debug.launch
new file mode 100644
index 00000000..01c3ed00
--- /dev/null
+++ b/robots/LoCoBot/locobot_control/launch/vslam_debug.launch
@@ -0,0 +1,122 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/robots/LoCoBot/locobot_control/src/locobot_controller.cpp b/robots/LoCoBot/locobot_control/src/locobot_controller.cpp
index 0932b96f..918512fe 100644
--- a/robots/LoCoBot/locobot_control/src/locobot_controller.cpp
+++ b/robots/LoCoBot/locobot_control/src/locobot_controller.cpp
@@ -73,7 +73,7 @@ LoCoBotController::~LoCoBotController() {
if (use_group_["arm"]) {
if (!torque_control_) {
std::map restJntsMap;
- float restJnts[5] = {0, -0.3890, 1.617, -0.1812, 0.0153};
+ float restJnts[5] = {0, -1.30, 1.617, 0.5, 0};
restJntsMap["joint_1"] = restJnts[0];
restJntsMap["joint_2"] = restJnts[1];
restJntsMap["joint_3"] = restJnts[2];
diff --git a/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/global_costmap_params_with_map.yaml b/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/global_costmap_params_with_map.yaml
index 70cf8c7b..f49c6f8c 100644
--- a/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/global_costmap_params_with_map.yaml
+++ b/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/global_costmap_params_with_map.yaml
@@ -1,6 +1,6 @@
global_costmap:
- global_frame: /map
- robot_base_frame: /base_link
+ global_frame: map
+ robot_base_frame: base_link
update_frequency: 1.0
publish_frequency: 0.5
static_map: true
diff --git a/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/global_map_extra.yaml b/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/global_map_extra.yaml
index 993bcc56..5f899c24 100644
--- a/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/global_map_extra.yaml
+++ b/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/global_map_extra.yaml
@@ -1,5 +1,5 @@
static_layer:
- map_topic: "/occupancy_map"
+ map_topic: "occupancy_map"
first_map_only: false
inflation_layer:
diff --git a/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/local_costmap_params.yaml b/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/local_costmap_params.yaml
index b71c5ef8..cd51ed6c 100644
--- a/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/local_costmap_params.yaml
+++ b/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/local_costmap_params.yaml
@@ -1,6 +1,6 @@
local_costmap:
global_frame: map
- robot_base_frame: /base_link
+ robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
diff --git a/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/local_map_extra.yaml b/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/local_map_extra.yaml
index 993bcc56..5f899c24 100644
--- a/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/local_map_extra.yaml
+++ b/robots/LoCoBot/locobot_navigation/base_navigation/config/turtlebot/local_map_extra.yaml
@@ -1,5 +1,5 @@
static_layer:
- map_topic: "/occupancy_map"
+ map_topic: "occupancy_map"
first_map_only: false
inflation_layer:
diff --git a/robots/LoCoBot/locobot_navigation/base_navigation/launch/turtlebot_move_base.launch b/robots/LoCoBot/locobot_navigation/base_navigation/launch/turtlebot_move_base.launch
index c010bcb6..59e7e473 100644
--- a/robots/LoCoBot/locobot_navigation/base_navigation/launch/turtlebot_move_base.launch
+++ b/robots/LoCoBot/locobot_navigation/base_navigation/launch/turtlebot_move_base.launch
@@ -25,9 +25,9 @@
-
+ ns="global_costmap" /> -->
diff --git a/robots/LoCoBot/locobot_navigation/base_navigation/nodes/mapToGrid.py b/robots/LoCoBot/locobot_navigation/base_navigation/nodes/mapToGrid.py
index 4687f2db..56160a0c 100755
--- a/robots/LoCoBot/locobot_navigation/base_navigation/nodes/mapToGrid.py
+++ b/robots/LoCoBot/locobot_navigation/base_navigation/nodes/mapToGrid.py
@@ -109,6 +109,7 @@ def initGrid(self):
def updateGrid(self):
if self.points is None:
return
+ print(CELL_RESOLUTION, self.xCells, self.yCells, self.xMin, self.yMin, self.ocGrid)
self.grid.header.seq = self.grid.header.seq + 1
self.grid.header.stamp = rospy.Time.now()
self.grid.info.map_load_time = rospy.Time.now()
diff --git a/robots/LoCoBot/locobot_navigation/orb_slam2_ros/scripts/orb_slam2_ros/pcdlib.py b/robots/LoCoBot/locobot_navigation/orb_slam2_ros/scripts/orb_slam2_ros/pcdlib.py
index 8fc4898b..d7b89b6a 100644
--- a/robots/LoCoBot/locobot_navigation/orb_slam2_ros/scripts/orb_slam2_ros/pcdlib.py
+++ b/robots/LoCoBot/locobot_navigation/orb_slam2_ros/scripts/orb_slam2_ros/pcdlib.py
@@ -233,7 +233,7 @@ def get_current_pcd(self):
return None, None
num_frames = 0
num_pts = 0
- for KFid, ext_mat in self.extrinsic_mats.iteritems():
+ for KFid, ext_mat in self.extrinsic_mats.items():
if KFid not in self.pcd_pool_in_cam:
continue
num_frames += 1
@@ -244,7 +244,7 @@ def get_current_pcd(self):
all_pts = np.zeros((num_pts, 3))
all_colors = np.zeros((num_pts, 3))
cur_id = 0
- for KFid, ext_mat in self.extrinsic_mats.iteritems():
+ for KFid, ext_mat in self.extrinsic_mats.items():
if KFid not in self.pcd_pool_in_cam:
continue
pcd_in_cam, rgb = self.pcd_pool_in_cam[KFid]
diff --git a/robots/LoCoBot/locobot_navigation/orb_slam2_ros/scripts/orb_slam2_ros/vslam.py b/robots/LoCoBot/locobot_navigation/orb_slam2_ros/scripts/orb_slam2_ros/vslam.py
index be38b0fd..19dffe44 100644
--- a/robots/LoCoBot/locobot_navigation/orb_slam2_ros/scripts/orb_slam2_ros/vslam.py
+++ b/robots/LoCoBot/locobot_navigation/orb_slam2_ros/scripts/orb_slam2_ros/vslam.py
@@ -253,7 +253,7 @@ def get_occupancy_map(self):
xcells = (int((self.x_max - self.x_min) / self.map_resultion)) + 1
ycells = (int((self.y_max - self.y_min) / self.map_resultion)) + 1
occ_map = np.zeros(xcells * ycells)
- return occ_map, xcells, ycells, self.x_min, self.y_min
+ return occ_map.astype(np.uint8).tolist(), xcells, ycells, self.x_min, self.y_min
(self.x_min, self.y_min, self.x_max, self.y_max) = self._calc_grid_bds(pts)
@@ -268,7 +268,7 @@ def get_occupancy_map(self):
pts = pts[:, 1] * xcells + pts[:, 0]
occ_map = np.zeros(xcells * ycells)
occ_map[pts] = self.obstacle_cost
- return occ_map, xcells, ycells, self.x_min, self.y_min
+ return occ_map.astype(np.uint8).tolist(), xcells, ycells, self.x_min, self.y_min
def _pub_occupancy_map(self):
occ_map, width, height, x_min, y_min = self.get_occupancy_map()
@@ -367,7 +367,7 @@ def get_link_transform(self, src, tgt):
def _init_occupancy_map(self):
grid = OccupancyGrid()
grid.header.seq = 1
- grid.header.frame_id = "/map"
+ grid.header.frame_id = "map"
grid.info.origin.position.z = 0
grid.info.origin.orientation.x = 0
grid.info.origin.orientation.y = 0
diff --git a/src/pyrobot/cfg/locobot_config.py b/src/pyrobot/cfg/locobot_config.py
index bfcd6119..87b0b1db 100644
--- a/src/pyrobot/cfg/locobot_config.py
+++ b/src/pyrobot/cfg/locobot_config.py
@@ -122,9 +122,9 @@
# reference link name of the visual SLAM system, the pose of this frame
# in the first time step will be used to define
# the origin/orientation of the world frame
-_BASEC.VSLAM.VSLAM_BASE_FRAME = "/base_link"
+_BASEC.VSLAM.VSLAM_BASE_FRAME = "base_link"
# RGB camera center frame name
-_BASEC.VSLAM.RGB_CAMERA_CENTER_FRAME = "/camera_color_optical_frame"
+_BASEC.VSLAM.RGB_CAMERA_CENTER_FRAME = "camera_color_optical_frame"
# minimum depth values to be considered as valid
_BASEC.VSLAM.DEPTH_MIN = 0.2
# maximum depth values to be considered as valid