rdk

package module
v0.2.7 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Dec 16, 2022 License: AGPL-3.0 Imports: 0 Imported by: 0

README

RDK (Robot Development Kit)

PkgGoDev

Viam provides an open source robot architecture that provides robotics functionality via simple APIs

Website: viam.com

Documentation: docs.viam.com

Cloud App: app.viam.com

Contact

Building and Using

Dependencies
  • Install make.
  • Run make setup to install dev environment requirements.
Build and Run
  • Build: make server. Then run ./bin/<your architecture>/server [parameters]
  • Run without building: go run web/cmd/server/main.go [parameters]

Example with a dummy configuration: go run web/cmd/server/main.go -config etc/configs/fake.json. Then visit http://localhost:8080 to access remote control.

Examples
  • SimpleServer - example for creating a simple custom server.
  • MySensor - example for creating a custom sensor.
  • MyComponent - example for creating a custom resource subtype.
SDKs

Multiple SDKs are available for writing client applications that interface with the Viam RDK.

Development

Sign the Contribution Agreement before submitting pull requests.

API

The API is defined with Protocol Buffers/gRPC which can be found at https://github.com/viamrobotics/api.

Conventions
Frontend

To start the client development environment, first run the same go run command mentioned in Building and Using, but with the environmental variable ENV=development (e.g. ENV=development go run web/cmd/server/main.go -debug -config etc/configs/fake.json).

Then navigate to web/frontend and run npm start in a new terminal tab. Visit localhost:8080 to view the app, not localhost:5173. The latter is a hot module replacement server that rebuilds frontend asset changes.

Frontend against a remote host

See documentation in Direct Remote Control.

License check

We run LicenseFinder in CI to verify 3rd-party libraries have approved software licenses. If you add a 3rd-party library to this project, please run make license to verify that it can be used.

License

Copyright 2021-2022 Viam Inc.

AGPLv3 - See LICENSE file

Documentation

Overview

Package rdk TODO

Directories

Path Synopsis
cli
Package cli contains all business logic needed by the CLI command.
Package cli contains all business logic needed by the CLI command.
cmd
Package main is the CLI command itself.
Package main is the CLI command itself.
cmd
dump_resources
Package main dumps all registered resources.
Package main dumps all registered resources.
components
arm
Package arm defines the arm that a robot uses to manipulate objects.
Package arm defines the arm that a robot uses to manipulate objects.
arm/eva
Package eva implements the Eva robot from Automata.
Package eva implements the Eva robot from Automata.
arm/fake
Package fake implements a fake arm.
Package fake implements a fake arm.
arm/register
Package register registers all relevant arms
Package register registers all relevant arms
arm/trossen
Package trossen implements arms from Trossen Robotics.
Package trossen implements arms from Trossen Robotics.
arm/universalrobots
Package universalrobots implements the UR arm from Universal Robots.
Package universalrobots implements the UR arm from Universal Robots.
arm/wrapper
Package wrapper is a package that defines an implementation that wraps a partially implemented arm
Package wrapper is a package that defines an implementation that wraps a partially implemented arm
arm/xarm
Package xarm implements some xArms.
Package xarm implements some xArms.
arm/yahboom
Package yahboom implements a yahboom based robot.
Package yahboom implements a yahboom based robot.
audioinput
Package audioinput defines an audio capturing device.
Package audioinput defines an audio capturing device.
audioinput/fake
Package fake implements a fake audio input.
Package fake implements a fake audio input.
audioinput/microphone
Package microphone implements a microphone audio input.
Package microphone implements a microphone audio input.
audioinput/register
Package register registers all relevant audio inputs and also subtype specific functions
Package register registers all relevant audio inputs and also subtype specific functions
base
Package base defines the base that a robot uses to move around.
Package base defines the base that a robot uses to move around.
base/agilex
Package limo implements the AgileX Limo base
Package limo implements the AgileX Limo base
base/boat
Package boat implements a base for a boat with support for N motors in any position or angle This is an Experimental package
Package boat implements a base for a boat with support for N motors in any position or angle This is an Experimental package
base/fake
Package fake implements a fake base.
Package fake implements a fake base.
base/register
Package register registers all relevant bases
Package register registers all relevant bases
base/wheeled
Package wheeled implements some bases, like a wheeled base.
Package wheeled implements some bases, like a wheeled base.
board
Package board defines the interfaces that typically live on a single-board computer such as a Raspberry Pi.
Package board defines the interfaces that typically live on a single-board computer such as a Raspberry Pi.
board/arduino
Package arduino implements the arduino board and some peripherals.
Package arduino implements the arduino board and some peripherals.
board/beaglebone
Package beaglebone implements a beaglebone based board.
Package beaglebone implements a beaglebone based board.
board/commonsysfs
Package commonsysfs implements a sysfs (https://en.wikipedia.org/wiki/Sysfs) based board.
Package commonsysfs implements a sysfs (https://en.wikipedia.org/wiki/Sysfs) based board.
board/fake
Package fake implements a fake board.
Package fake implements a fake board.
board/hat/pca9685
Package pca9685 implements a PCA9685 HAT.
Package pca9685 implements a PCA9685 HAT.
board/jetson
Package jetson implements a jetson based board.
Package jetson implements a jetson based board.
board/numato
Package numato is for numato IO boards.
Package numato is for numato IO boards.
board/pi
Package pi implements a Board and its related interfaces for a Raspberry Pi.
Package pi implements a Board and its related interfaces for a Raspberry Pi.
board/pi/common
Package picommon contains shared information for supported and non-supported pi boards.
Package picommon contains shared information for supported and non-supported pi boards.
board/register
Package register registers all relevant Boards and also subtype specific functions
Package register registers all relevant Boards and also subtype specific functions
board/ti
Package ti implements a ti based board.
Package ti implements a ti based board.
camera
Package camera defines an image capturing device.
Package camera defines an image capturing device.
camera/align
Package align defines the camera models that are used to align a color camera's output with a depth camera's output, in order to make point clouds.
Package align defines the camera models that are used to align a color camera's output with a depth camera's output, in order to make point clouds.
camera/fake
Package fake implements a fake camera.
Package fake implements a fake camera.
camera/ffmpeg
Package ffmpeg provides an implementation for an ffmpeg based camera
Package ffmpeg provides an implementation for an ffmpeg based camera
camera/register
Package register registers all relevant cameras and also subtype specific functions
Package register registers all relevant cameras and also subtype specific functions
camera/transformpipeline
Package transformpipeline defines image sources that apply transforms on images, and can be composed into an image transformation pipeline.
Package transformpipeline defines image sources that apply transforms on images, and can be composed into an image transformation pipeline.
camera/velodyne
Package velodyne implements a general velodyne LIDAR as a camera.
Package velodyne implements a general velodyne LIDAR as a camera.
camera/videosource
Package videosource defines various image sources typically registered as cameras in the API.
Package videosource defines various image sources typically registered as cameras in the API.
encoder
Package encoder implements the encoder component
Package encoder implements the encoder component
encoder/fake
Package fake implements a fake encoder.
Package fake implements a fake encoder.
gantry
Package gantry contains a gRPC based gantry client.
Package gantry contains a gRPC based gantry client.
gantry/fake
Package fake implements a fake gantry.
Package fake implements a fake gantry.
gantry/multiaxis
Package multiaxis implements a multi-axis gantry.
Package multiaxis implements a multi-axis gantry.
gantry/oneaxis
Package oneaxis implements a one-axis gantry.
Package oneaxis implements a one-axis gantry.
gantry/register
Package register registers all relevant gantries
Package register registers all relevant gantries
generic
Package generic contains a gRPC based generic client.
Package generic contains a gRPC based generic client.
generic/register
Package register registers the generic component
Package register registers the generic component
gripper
Package gripper contains a gRPC based gripper client.
Package gripper contains a gRPC based gripper client.
gripper/fake
Package fake implements a fake gripper.
Package fake implements a fake gripper.
gripper/register
Package register registers all relevant grippers and also subtype specific functions
Package register registers all relevant grippers and also subtype specific functions
gripper/robotiq
Package robotiq implements the gripper from robotiq.
Package robotiq implements the gripper from robotiq.
gripper/softrobotics
Package softrobotics implements the vacuum gripper from Soft Robotics.
Package softrobotics implements the vacuum gripper from Soft Robotics.
gripper/trossen
Package trossen implements a trossen gripper.
Package trossen implements a trossen gripper.
gripper/vgripper/v1
Package vgripper implements versions of the Viam gripper.
Package vgripper implements versions of the Viam gripper.
gripper/yahboom
Package yahboom implements a yahboom based gripper.
Package yahboom implements a yahboom based gripper.
input
Package input contains a gRPC based input controller client.
Package input contains a gRPC based input controller client.
input/fake
Package fake implements a fake input controller.
Package fake implements a fake input controller.
input/gamepad
Package gamepad implements a linux gamepad as an input controller.
Package gamepad implements a linux gamepad as an input controller.
input/gpio
Package gpio implements a gpio/adc based input.Controller.
Package gpio implements a gpio/adc based input.Controller.
input/mux
Package mux implements a multiplexed input controller.
Package mux implements a multiplexed input controller.
input/register
Package register registers all relevant inputs
Package register registers all relevant inputs
input/webgamepad
Package webgamepad implements a web based input controller.
Package webgamepad implements a web based input controller.
motor
Package motor contains a gRPC bases motor client
Package motor contains a gRPC bases motor client
motor/dimensionengineering
Package dimensionengineering contains implementations of the dimensionengineering motor controls
Package dimensionengineering contains implementations of the dimensionengineering motor controls
motor/dmc4000
Package dmc4000 implements stepper motors behind a Galil DMC4000 series motor controller
Package dmc4000 implements stepper motors behind a Galil DMC4000 series motor controller
motor/fake
Package fake implements a fake motor.
Package fake implements a fake motor.
motor/gpio
Package gpio implements a GPIO based motor.
Package gpio implements a GPIO based motor.
motor/gpiostepper
Package gpiostepper implements a GPIO based stepper motor.
Package gpiostepper implements a GPIO based stepper motor.
motor/i2cmotors
Package ezopmp is a motor driver for the hydrogarden pump
Package ezopmp is a motor driver for the hydrogarden pump
motor/register
Package register registers all relevant motors
Package register registers all relevant motors
motor/roboclaw
Package roboclaw is the driver for the roboclaw motor drivers
Package roboclaw is the driver for the roboclaw motor drivers
motor/tmcstepper
Package tmcstepper implements a TMC stepper motor.
Package tmcstepper implements a TMC stepper motor.
movementsensor
Package movementsensor defines the interfaces of a MovementSensor
Package movementsensor defines the interfaces of a MovementSensor
movementsensor/adxl345
Package adxl345 implements the MovementSensor interface for the ADXL345 accelerometer attached to the I2C bus of the robot (the chip supports communicating over SPI as well, but this package does not support that interface).
Package adxl345 implements the MovementSensor interface for the ADXL345 accelerometer attached to the I2C bus of the robot (the chip supports communicating over SPI as well, but this package does not support that interface).
movementsensor/cameramono
Package cameramono implements a visual odemetry movement sensor based ona single camera stream This is an Experimental package
Package cameramono implements a visual odemetry movement sensor based ona single camera stream This is an Experimental package
movementsensor/fake
Package fake is a fake MovementSensor for testing
Package fake is a fake MovementSensor for testing
movementsensor/gpsnmea
Package gpsnmea implements an NMEA serial gps.
Package gpsnmea implements an NMEA serial gps.
movementsensor/gpsrtk
Package gpsrtk defines a gps and an rtk correction source which sends rtcm data to a child gps This is an Experimental package
Package gpsrtk defines a gps and an rtk correction source which sends rtcm data to a child gps This is an Experimental package
movementsensor/imuvectornav
Package imuvectornav implement vectornav imu
Package imuvectornav implement vectornav imu
movementsensor/imuwit
Package imuwit implements wit imus.
Package imuwit implements wit imus.
movementsensor/mpu6050
Package mpu6050 implements the movementsensor interface for an MPU-6050 6-axis accelerometer.
Package mpu6050 implements the movementsensor interface for an MPU-6050 6-axis accelerometer.
movementsensor/register
Package register registers all relevant MovementSensors
Package register registers all relevant MovementSensors
posetracker
Package posetracker contains the interface and gRPC infrastructure for a pose tracker component
Package posetracker contains the interface and gRPC infrastructure for a pose tracker component
register
Package register registers all components
Package register registers all components
sensor
Package sensor contains a gRPC based sensor client.
Package sensor contains a gRPC based sensor client.
sensor/bme280
Package bme280 implements a bme280 sensor for temperature, humidity, and pressure.
Package bme280 implements a bme280 sensor for temperature, humidity, and pressure.
sensor/charge
Package charge implements a charge controller sensor
Package charge implements a charge controller sensor
sensor/ds18b20
Package ds18b20 implements a 1-wire temperature sensor
Package ds18b20 implements a 1-wire temperature sensor
sensor/fake
Package fake implements a fake Sensor.
Package fake implements a fake Sensor.
sensor/register
Package register registers all relevant Sensors
Package register registers all relevant Sensors
sensor/ultrasonic
Package ultrasonic implements an ultrasonic sensor based of the yahboom ultrasonic sensor
Package ultrasonic implements an ultrasonic sensor based of the yahboom ultrasonic sensor
servo
Package servo contains a gRPC bases servo client
Package servo contains a gRPC bases servo client
servo/fake
Package fake implements a fake servo.
Package fake implements a fake servo.
servo/gpio
Package gpio implements a pin based servo
Package gpio implements a pin based servo
servo/register
Package register registers all relevant servos
Package register registers all relevant servos
Package config defines the structures to configure a robot and its connected parts.
Package config defines the structures to configure a robot and its connected parts.
Package control package for feedback loop controls This is an Experimental package
Package control package for feedback loop controls This is an Experimental package
Package data contains the code involved with Viam's Data Management Platform for automatically collecting component readings from robots.
Package data contains the code involved with Viam's Data Management Platform for automatically collecting component readings from robots.
Package discovery implements types to support robot component discovery.
Package discovery implements types to support robot component discovery.
etc
analyzecoverage
Package main is a go test analyzer that publishes results to a MongoDB database.
Package main is a go test analyzer that publishes results to a MongoDB database.
analyzetests
Package main is a go test analyzer that publishes results to a MongoDB database.
Package main is a go test analyzer that publishes results to a MongoDB database.
Package examples contain a few examples of using the RDK.
Package examples contain a few examples of using the RDK.
mycomponent
Package mycomponent contains an example on creating a custom resource subtype.
Package mycomponent contains an example on creating a custom resource subtype.
mycomponent/client
Package main tests out a MyComponent client.
Package main tests out a MyComponent client.
mycomponent/component
Package component implements MyComponent.
Package component implements MyComponent.
mycomponent/proto/api/component/mycomponent/v1
Package v1 is a reverse proxy.
Package v1 is a reverse proxy.
mycomponent/server
Package main is a sample of a user defined and implemented component type
Package main is a sample of a user defined and implemented component type
mysensor
Package mysensor contains an example on creating a custom model.
Package mysensor contains an example on creating a custom model.
mysensor/client
Package main tests out the mySensor component type.
Package main tests out the mySensor component type.
mysensor/server
Package main is an example of a custom viam server.
Package main is an example of a custom viam server.
simpleserver
Package main shows a simple server with a fake arm.
Package main shows a simple server with a fake arm.
Package grpc provides grpc utilities.
Package grpc provides grpc utilities.
ml
Package ml provides some fundamental machine learning primitives.
Package ml provides some fundamental machine learning primitives.
inference
Package inference allows users to do inference through tflite (tf, pytorch, etc in the future)
Package inference allows users to do inference through tflite (tf, pytorch, etc in the future)
Package motionplan is a motion planning library.
Package motionplan is a motion planning library.
Package octree implements a octree representation of pointclouds for easy traversal and storage of probability and color data
Package octree implements a octree representation of pointclouds for easy traversal and storage of probability and color data
Package operation manages operation ids
Package operation manages operation ids
Package pointcloud defines a point cloud and provides an implementation for one.
Package pointcloud defines a point cloud and provides an implementation for one.
Package protoutils are a collection of util methods for using proto in rdk
Package protoutils are a collection of util methods for using proto in rdk
Package referenceframe defines the api and does the math of translating between reference frames Useful for if you have a camera, connected to a gripper, connected to an arm, and need to translate the camera reference frame to the arm reference frame, if you've found something in the camera, and want to move the gripper + arm to get it.
Package referenceframe defines the api and does the math of translating between reference frames Useful for if you have a camera, connected to a gripper, connected to an arm, and need to translate the camera reference frame to the arm reference frame, if you've found something in the camera, and want to move the gripper + arm to get it.
Package registry operates the global registry of robotic parts.
Package registry operates the global registry of robotic parts.
Package resource contains a Resource type that can be used to hold information about a robot component or service.
Package resource contains a Resource type that can be used to hold information about a robot component or service.
Package rimage defines fundamental image and color processing primitives.
Package rimage defines fundamental image and color processing primitives.
cmd/stream_camera
Package main streams a specific camera over WebRTC.
Package main streams a specific camera over WebRTC.
depthadapter
Package depthadapter is a simple package that turns a DepthMap into a point cloud using intrinsic parameters of a camera.
Package depthadapter is a simple package that turns a DepthMap into a point cloud using intrinsic parameters of a camera.
transform
Package transform provides image transformation utilities relying on camera parameters.
Package transform provides image transformation utilities relying on camera parameters.
transform/cmd/depth_to_color
Get the coordinates of a depth pixel in the depth map in the reference frame of the color image $./depth_to_color -conf=/path/to/intrinsics/extrinsic/file X Y Z
Get the coordinates of a depth pixel in the depth map in the reference frame of the color image $./depth_to_color -conf=/path/to/intrinsics/extrinsic/file X Y Z
transform/cmd/extrinsic_calibration
Given at least 4 corresponding points, and the intrinsic matrices of both cameras, computes the rigid transform (rotation + translation) that would be the extrinsic transformation from camera 1 to camera 2.
Given at least 4 corresponding points, and the intrinsic matrices of both cameras, computes the rigid transform (rotation + translation) that would be the extrinsic transformation from camera 1 to camera 2.
Package robot defines the robot which is the root of all robotic parts.
Package robot defines the robot which is the root of all robotic parts.
client
Package client contains a gRPC based robot.Robot client.
Package client contains a gRPC based robot.Robot client.
framesystem
Package framesystem defines and implements the concept of a frame system.
Package framesystem defines and implements the concept of a frame system.
framesystem/parts
Package framesystemparts provides functionality around a list of framesystem parts
Package framesystemparts provides functionality around a list of framesystem parts
impl
Package robotimpl defines implementations of robot.Robot and robot.LocalRobot.
Package robotimpl defines implementations of robot.Robot and robot.LocalRobot.
server
Package server contains a gRPC based robot.Robot server implementation.
Package server contains a gRPC based robot.Robot server implementation.
web
Package web provides gRPC/REST/GUI APIs to control and monitor a robot.
Package web provides gRPC/REST/GUI APIs to control and monitor a robot.
web/options
Package weboptions provides Options for configuring a web server
Package weboptions provides Options for configuring a web server
web/stream
Package webstream provides controls for streaming from the web server.
Package webstream provides controls for streaming from the web server.
ros
Package ros implements functionality that bridges the gap between `rdk` and ROS
Package ros implements functionality that bridges the gap between `rdk` and ROS
rosbag_parser/cmd
Package main is a rosbag parser.
Package main is a rosbag parser.
services
armremotecontrol
Package armremotecontrol implements a remote control for a arm.
Package armremotecontrol implements a remote control for a arm.
armremotecontrol/builtin
Package builtin implements a remote control for a arm.
Package builtin implements a remote control for a arm.
armremotecontrol/register
Package register registers all relevant armremotecontrol models and also subtype specific functions
Package register registers all relevant armremotecontrol models and also subtype specific functions
baseremotecontrol
Package baseremotecontrol implements a remote control for a base.
Package baseremotecontrol implements a remote control for a base.
baseremotecontrol/builtin
Package builtin implements a remote control for a base.
Package builtin implements a remote control for a base.
baseremotecontrol/register
Package register registers all relevant baseremotecontrol models and also subtype specific functions
Package register registers all relevant baseremotecontrol models and also subtype specific functions
datamanager
Package datamanager contains a gRPC based datamanager service server
Package datamanager contains a gRPC based datamanager service server
datamanager/builtin
Package builtin contains a service type that can be used to capture data from a robot's components.
Package builtin contains a service type that can be used to capture data from a robot's components.
datamanager/datacapture
Package datacapture contains tools for interacting with Viam datacapture files.
Package datacapture contains tools for interacting with Viam datacapture files.
datamanager/datasync
Package datasync contains interfaces for syncing data from robots to the app.viam.com cloud.
Package datasync contains interfaces for syncing data from robots to the app.viam.com cloud.
datamanager/internal
Package internal implements a data manager service definition with additional exported functions for the purpose of testing
Package internal implements a data manager service definition with additional exported functions for the purpose of testing
datamanager/model
Package model implements model storage/deployment client.
Package model implements model storage/deployment client.
datamanager/register
Package register registers all relevant datamanager models and also subtype specific functions
Package register registers all relevant datamanager models and also subtype specific functions
motion
Package motion contains a gRPC based motion client
Package motion contains a gRPC based motion client
motion/builtin
Package builtin implements a motion service.
Package builtin implements a motion service.
motion/register
Package register registers all relevant motion services and also subtype specific functions
Package register registers all relevant motion services and also subtype specific functions
navigation
Package navigation contains a navigation service, along with a gRPC server and client
Package navigation contains a navigation service, along with a gRPC server and client
navigation/builtin
Package builtin contains the default navigation service, along with a gRPC server and client
Package builtin contains the default navigation service, along with a gRPC server and client
navigation/register
Package register registers all relevant navigation models and also subtype specific functions
Package register registers all relevant navigation models and also subtype specific functions
register
Package register registers all services
Package register registers all services
sensors
Package sensors contains a gRPC based sensors service client
Package sensors contains a gRPC based sensors service client
sensors/builtin
Package builtin implements the default sensors service.
Package builtin implements the default sensors service.
sensors/register
Package register registers all relevant sensors models and also subtype specific functions
Package register registers all relevant sensors models and also subtype specific functions
shell
Package shell contains a shell service, along with a gRPC server and client
Package shell contains a shell service, along with a gRPC server and client
shell/builtin
Package builtin contains a shell service, along with a gRPC server and client
Package builtin contains a shell service, along with a gRPC server and client
shell/register
Package register registers all relevant shell models and also subtype specific functions
Package register registers all relevant shell models and also subtype specific functions
slam
Package slam implements simultaneous localization and mapping This is an Experimental package
Package slam implements simultaneous localization and mapping This is an Experimental package
slam/builtin
Package builtin implements simultaneous localization and mapping This is an Experimental package
Package builtin implements simultaneous localization and mapping This is an Experimental package
slam/internal
Package internal implements a slam service definition with additional exported functions for the purpose of testing
Package internal implements a slam service definition with additional exported functions for the purpose of testing
slam/register
Package register registers all relevant slam models and also subtype specific functions
Package register registers all relevant slam models and also subtype specific functions
vision
Package vision is the service that allows you to access various computer vision algorithms (like detection, segmentation, tracking, etc) that usually only require a camera or image input.
Package vision is the service that allows you to access various computer vision algorithms (like detection, segmentation, tracking, etc) that usually only require a camera or image input.
vision/builtin
Package builtin is the service that allows you to access various computer vision algorithms (like detection, segmentation, tracking, etc) that usually only require a camera or image input.
Package builtin is the service that allows you to access various computer vision algorithms (like detection, segmentation, tracking, etc) that usually only require a camera or image input.
vision/register
Package register registers all relevant vision models and also subtype specific functions
Package register registers all relevant vision models and also subtype specific functions
Package session provides support for robot session management.
Package session provides support for robot session management.
Package spatialmath defines spatial mathematical operations.
Package spatialmath defines spatial mathematical operations.
Package subtype contains a Service type that can be used to hold all resources of a certain subtype.
Package subtype contains a Service type that can be used to hold all resources of a certain subtype.
Package testutils implements test utilities.
Package testutils implements test utilities.
inject
Package inject provides dependency injected structures for mocking interfaces.
Package inject provides dependency injected structures for mocking interfaces.
robottestutils
Package robottestutils provides helper functions in testing
Package robottestutils provides helper functions in testing
Package utils contains all utility functions that currently have no better home than here.
Package utils contains all utility functions that currently have no better home than here.
Package vision implements computer vision algorithms.
Package vision implements computer vision algorithms.
chess
Package chess implements computer vision algorithms useful in chess.
Package chess implements computer vision algorithms useful in chess.
classification
Package classification implements a classifier for use as a visModel in the vision service
Package classification implements a classifier for use as a visModel in the vision service
delaunay
Package delaunay implements 2d Delaunay triangulation
Package delaunay implements 2d Delaunay triangulation
keypoints
Package keypoints contains the implementation of keypoints in an image.
Package keypoints contains the implementation of keypoints in an image.
objectdetection
Package objectdetection defines a functional way to create object detection pipelines by feeding in images from a gostream.VideoSource source.
Package objectdetection defines a functional way to create object detection pipelines by feeding in images from a gostream.VideoSource source.
objectdetection/cmd/color_detection
Package main is a color detection tool.
Package main is a color detection tool.
odometry
Package odometry implements functions for visual odometry
Package odometry implements functions for visual odometry
odometry/cmd
Package main is a motion estimation via visual odometry tool.
Package main is a motion estimation via visual odometry tool.
segmentation
Package segmentation implements object segmentation algorithms.
Package segmentation implements object segmentation algorithms.
web
Package web contains the root of a web server.
Package web contains the root of a web server.
cmd/directremotecontrol
Package main provides a utility to run a remote control only web server.
Package main provides a utility to run a remote control only web server.
cmd/server
Package main provides a server offering gRPC/REST/GUI APIs to control and monitor a robot.
Package main provides a server offering gRPC/REST/GUI APIs to control and monitor a robot.
server
Package server implements the entry point for running a robot web server.
Package server implements the entry point for running a robot web server.

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL