Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 6 additions & 1 deletion cloudslam/app.go
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ type AppClient struct {
PackageClient pbPackage.PackageServiceClient
SyncClient pbDataSync.DataSyncServiceClient
RobotClient pbApp.RobotServiceClient
HTTPClient *http.Client // used for downloading pcds of the current cloudslam session
HTTPClient *http.Client // used for downloading pcds of the current cloudslam session
logger logging.Logger
}

Expand Down Expand Up @@ -174,6 +174,11 @@ func hasEnabledDataCapture(comp *pbApp.ComponentConfig, sensorType slam.SensorTy
return false
}

// SLAMMapURL returns the app URL for viewing a SLAM map package.
func (app *AppClient) SLAMMapURL(mapName, version string) string {
return app.baseURL + "/robots?page=slam&name=" + mapName + "&version=" + version
}

// Close closes the app clients.
func (app *AppClient) Close() error {
// close any idle connections to prevent goleaks. Possibly redundant with DisableKeepAlives
Expand Down
90 changes: 84 additions & 6 deletions cloudslam/cloudslam.go
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@ type cloudslamWrapper struct {
activeJob atomic.Pointer[activeJobState] // nil when no job is running
lastPose atomic.Pointer[spatialmath.Pose]
lastPointCloudURL atomic.Pointer[string]
lastSessionErr atomic.Pointer[string] // non-nil when the last session ended with a failure
defaultpcd []byte

slamService slam.Service // the slam service that cloudslam will wrap
Expand Down Expand Up @@ -292,6 +293,19 @@ func (svc *cloudslamWrapper) activeMappingSessionThread(ctx context.Context) {
continue
}

// Check session metadata to detect failures.
metaResp, err := svc.app.CSClient.GetMappingSessionMetadataByID(ctx,
&pbCloudSLAM.GetMappingSessionMetadataByIDRequest{SessionId: job.id})
if err != nil {
svc.logger.Error(err)
} else if metaResp.GetSessionMetadata().GetEndStatus() == pbCloudSLAM.EndStatus_END_STATUS_FAIL {
errMsg := metaResp.GetSessionMetadata().GetErrorMsg()
svc.logger.Errorf("cloudslam session %s failed: %s", job.id, errMsg)
svc.lastSessionErr.Store(&errMsg)
svc.activeJob.Store(nil)
continue
}

// get the most recent pointcloud and position if there is an active job
req := &pbCloudSLAM.GetMappingSessionPointCloudRequest{SessionId: job.id}
resp, err := svc.app.CSClient.GetMappingSessionPointCloud(ctx, req)
Expand All @@ -313,6 +327,16 @@ func (svc *cloudslamWrapper) Position(ctx context.Context) (spatialmath.Pose, er
}

func (svc *cloudslamWrapper) PointCloudMap(ctx context.Context, returnEditedMap bool) (func() ([]byte, error), error) {
// If the last session failed, show a failure PCD regardless of map state.
if svc.lastSessionErr.Load() != nil {
failurePCD, err := generateFailurePCD()
if err != nil {
svc.logger.Warnf("failed to generate failure PCD: %v", err)
return toChunkedFunc(svc.defaultpcd), nil
}
return toChunkedFunc(failurePCD), nil
}

currMap := *svc.lastPointCloudURL.Load()

if currMap == "" {
Expand Down Expand Up @@ -367,6 +391,7 @@ func (svc *cloudslamWrapper) DoCommand(ctx context.Context, req map[string]inter
svc.activeJob.Store(&activeJobState{id: jobID, startedAt: time.Now()})
svc.lastPose.Store(&initPose)
svc.lastPointCloudURL.Store(&initPCDURL)
svc.lastSessionErr.Store(nil)

if isUpdating {
resp[updatingModeKey] = fmt.Sprintf("slam map found on machine, starting cloudslam in updating mode. Map "+
Expand Down Expand Up @@ -414,8 +439,7 @@ func (svc *cloudslamWrapper) StopJob(ctx context.Context) (string, error) {

svc.activeJob.Store(nil)
packageName := strings.Split(resp.GetPackageId(), "/")[1]
packageURL := svc.app.baseURL + "/robots?page=slam&name=" + packageName + "&version=" + resp.GetVersion()
return packageURL, nil
return svc.app.SLAMMapURL(packageName, resp.GetVersion()), nil
}

// StartJob starts a cloudslam job with the requested map name. Currently assumes a set of config parameters.
Expand Down Expand Up @@ -505,22 +529,28 @@ func (svc *cloudslamWrapper) ParseSensorsForPackage() ([]interface{}, error) {
return sensorMetadata, nil
}

// generateProgressRingPCD generates a point cloud of a progress arc indicating elapsed time.
// The arc grows clockwise from 0 to a full circle over progressRingDuration, giving the user
// visual feedback while waiting for the first cloudslam map to appear.
// generateProgressRingPCD generates a point cloud of a progress arc with status text inside.
// The arc grows from 0 to a full circle over progressRingDuration. Text reading
// "WAITING FOR / SESSION TO START" is rendered inside the ring using a 5×7 dot-matrix font
// so the viewer can clearly distinguish this from a real map.
func generateProgressRingPCD(elapsed time.Duration) ([]byte, error) {
const (
numPoints = 360
radius = 1000.0 // mm
progressRingDuration = 5 * time.Minute
pixelSize = 18.0 // mm per dot — fits both text lines within the ring
line1 = "WAITING FOR"
line2 = "SESSION TO START"
fontRows = 7
lineGapRows = 2
)

// Always show at least a small arc so the user sees something immediately.
fraction := math.Max(0.02, math.Min(elapsed.Seconds()/progressRingDuration.Seconds(), 1.0))
filledPoints := int(fraction * numPoints)

pc := pointcloud.NewBasicEmpty()
for i := 0; i < filledPoints; i++ {
for i := range filledPoints {
angle := float64(i) / numPoints * 2 * math.Pi
x := radius * math.Cos(angle)
y := radius * math.Sin(angle)
Expand All @@ -529,6 +559,54 @@ func generateProgressRingPCD(elapsed time.Duration) ([]byte, error) {
}
}

// Center both lines vertically around the origin.
// line1Y is the y coordinate of the top pixel row of line 1;
// with pixelSize=18 both lines fit comfortably within the 1000mm ring radius.
line1Y := float64(fontRows+lineGapRows+fontRows-1) / 2 * pixelSize
line2Y := line1Y - float64(fontRows+lineGapRows)*pixelSize

// Center each line horizontally. Width = (nChars×6 − 1) × pixelSize.
line1X := -float64(len(line1)*6-1) * pixelSize / 2
line2X := -float64(len(line2)*6-1) * pixelSize / 2

if err := addTextToPCD(pc, line1, line1X, line1Y, pixelSize); err != nil {
return nil, err
}
if err := addTextToPCD(pc, line2, line2X, line2Y, pixelSize); err != nil {
return nil, err
}

var buf bytes.Buffer
if err := pointcloud.ToPCD(pc, &buf, pointcloud.PCDAscii); err != nil {
return nil, err
}
return buf.Bytes(), nil
}

// generateFailurePCD generates a point cloud displaying "SESSION FAILED" to indicate the mapping session ended with an error.
func generateFailurePCD() ([]byte, error) {
const (
pixelSize = 18.0 // mm per dot
line1 = "SESSION"
line2 = "FAILED"
fontRows = 7
lineGapRows = 2
)

pc := pointcloud.NewBasicEmpty()

line1Y := float64(fontRows+lineGapRows+fontRows-1) / 2 * pixelSize
line2Y := line1Y - float64(fontRows+lineGapRows)*pixelSize
line1X := -float64(len(line1)*6-1) * pixelSize / 2
line2X := -float64(len(line2)*6-1) * pixelSize / 2

if err := addTextToPCD(pc, line1, line1X, line1Y, pixelSize); err != nil {
return nil, err
}
if err := addTextToPCD(pc, line2, line2X, line2Y, pixelSize); err != nil {
return nil, err
}

var buf bytes.Buffer
if err := pointcloud.ToPCD(pc, &buf, pointcloud.PCDAscii); err != nil {
return nil, err
Expand Down
3 changes: 1 addition & 2 deletions cloudslam/createpackage.go
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,7 @@ func (svc *cloudslamWrapper) UploadPackage(ctx context.Context, mapName string)
}

// return a link for where to find the package
packageURL := svc.app.baseURL + "/robots?name=" + mapName + "&version=" + packageVersion
return packageURL, nil
return svc.app.SLAMMapURL(mapName, packageVersion), nil
}

// uploadArchive creates a tar/archive of the SLAM map and uploads it to app using the package APIs.
Expand Down
51 changes: 51 additions & 0 deletions cloudslam/pcdtext.go
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
package cloudslam

import (
"github.com/golang/geo/r3"
"go.viam.com/rdk/pointcloud"
)

// font5x7 defines a 5×7 dot-matrix bitmap for each character used in status text.
// Each entry is 7 bytes (one per row, top to bottom). Within each byte,
// bit 4 is the leftmost column and bit 0 is the rightmost.
var font5x7 = map[byte][7]byte{
' ': {},
'A': {0b01110, 0b10001, 0b10001, 0b11111, 0b10001, 0b10001, 0b10001},
'E': {0b11111, 0b10000, 0b11110, 0b10000, 0b10000, 0b10000, 0b11111},
'F': {0b11111, 0b10000, 0b11110, 0b10000, 0b10000, 0b10000, 0b10000},
'G': {0b01110, 0b10001, 0b10000, 0b10110, 0b10001, 0b10001, 0b01110},
'I': {0b11111, 0b00100, 0b00100, 0b00100, 0b00100, 0b00100, 0b11111},
'D': {0b11110, 0b10001, 0b10001, 0b10001, 0b10001, 0b10001, 0b11110},
'L': {0b10000, 0b10000, 0b10000, 0b10000, 0b10000, 0b10000, 0b11111},
'N': {0b10001, 0b11001, 0b10101, 0b10011, 0b10001, 0b10001, 0b10001},
'O': {0b01110, 0b10001, 0b10001, 0b10001, 0b10001, 0b10001, 0b01110},
'R': {0b11110, 0b10001, 0b10001, 0b11110, 0b10100, 0b10010, 0b10001},
'S': {0b01110, 0b10001, 0b10000, 0b01110, 0b00001, 0b10001, 0b01110},
'T': {0b11111, 0b00100, 0b00100, 0b00100, 0b00100, 0b00100, 0b00100},
'W': {0b10001, 0b10001, 0b10001, 0b10101, 0b10101, 0b11011, 0b10001},
}

// addTextToPCD renders a string into a point cloud using a 5×7 dot-matrix font.
// (x0, y0) is the top-left corner of the first character in mm.
// pixelSize controls the spacing between dots in mm.
func addTextToPCD(pc pointcloud.PointCloud, text string, x0, y0, pixelSize float64) error {
for i, ch := range []byte(text) {
bitmap, ok := font5x7[ch]
if !ok {
continue
}
charX := x0 + float64(i)*6*pixelSize
for row := range 7 {
for col := range 5 {
if bitmap[row]&(1<<(4-col)) != 0 {
px := charX + float64(col)*pixelSize
py := y0 - float64(row)*pixelSize
if err := pc.Set(r3.Vector{X: px, Y: py, Z: 0}, pointcloud.NewBasicData()); err != nil {
return err
}
}
}
}
}
return nil
}