Documentation
¶
Overview ¶
Package rdk defines the Robot Development Kit. This is the open-source, on-robot portion of the Viam platform, providing viam-server and the Go SDK.
Directories
¶
Path | Synopsis |
---|---|
Package cli contains all business logic needed by the CLI command.
|
Package cli contains all business logic needed by the CLI command. |
viam
Package main is the CLI command itself.
|
Package main is the CLI command itself. |
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/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 API specific functions
|
Package register registers all relevant audio inputs and also API 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/fake
Package fake implements a fake base.
|
Package fake implements a fake base. |
base/kinematicbase
Package kinematicbase contains wrappers that augment bases with information needed for higher level control over the base
|
Package kinematicbase contains wrappers that augment bases with information needed for higher level control over the 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/beaglebone
Package beaglebone implements a beaglebone based board.
|
Package beaglebone implements a beaglebone based board. |
board/customlinux
Package customlinux implements a board running Linux.
|
Package customlinux implements a board running Linux. |
board/fake
Package fake implements a fake board.
|
Package fake implements a fake board. |
board/genericlinux
Package genericlinux implements a Linux-based board making heavy use of sysfs (https://en.wikipedia.org/wiki/Sysfs).
|
Package genericlinux implements a Linux-based board making heavy use of sysfs (https://en.wikipedia.org/wiki/Sysfs). |
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 API specific functions
|
Package register registers all relevant Boards and also API specific functions |
board/ti
Package ti implements a ti based board.
|
Package ti implements a ti based board. |
board/upboard
Package upboard implements an Intel based board.
|
Package upboard implements an Intel 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 which always returns the same image with a user specified resolution.
|
Package fake implements a fake camera which always returns the same image with a user specified resolution. |
camera/ffmpeg
Package ffmpeg provides an implementation for an ffmpeg based camera
|
Package ffmpeg provides an implementation for an ffmpeg based camera |
camera/platforms/jetson
Package jetsoncamera contains information about the daughterboards and camera modules that are supported on jetson platforms.
|
Package jetsoncamera contains information about the daughterboards and camera modules that are supported on jetson platforms. |
camera/register
Package register registers all relevant cameras and also API specific functions
|
Package register registers all relevant cameras and also API specific functions |
camera/replaypcd
Package replaypcd implements a replay camera that can return point cloud data.
|
Package replaypcd implements a replay camera that can return point cloud data. |
camera/rtsp
Package rtsp implements an RTSP camera client for RDK
|
Package rtsp implements an RTSP camera client for RDK |
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/ultrasonic
Package ultrasonic provides an implementation for an ultrasonic sensor wrapped as a camera
|
Package ultrasonic provides an implementation for an ultrasonic sensor wrapped as a camera |
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/ams
Package ams implements the AMS_AS5048 encoder
|
Package ams implements the AMS_AS5048 encoder |
encoder/fake
Package fake implements a fake encoder.
|
Package fake implements a fake encoder. |
encoder/incremental
Package incremental implements an incremental encoder
|
Package incremental implements an incremental encoder |
encoder/register
Package register registers all relevant MovementSensors
|
Package register registers all relevant MovementSensors |
encoder/single
Package single implements a single-wire odometer, such as LM393, as an encoder.
|
Package single implements a single-wire odometer, such as LM393, as an 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/register
Package register registers all relevant gantries
|
Package register registers all relevant gantries |
gantry/singleaxis
Package singleaxis implements a single-axis gantry.
|
Package singleaxis implements a single-axis gantry. |
generic
Package generic contains a gRPC based generic client.
|
Package generic contains a gRPC based generic client. |
generic/fake
Package fake implements a fake Generic component.
|
Package fake implements a fake Generic component. |
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 API specific functions
|
Package register registers all relevant grippers and also API 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/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 NOTE: This implementation is experimental and incomplete.
|
Package roboclaw is the driver for the roboclaw motor drivers NOTE: This implementation is experimental and incomplete. |
motor/tmcstepper
Package tmcstepper implements a TMC stepper motor.
|
Package tmcstepper implements a TMC stepper motor. |
motor/ulnstepper
Package uln28byj implements a GPIO based stepper motor (model: 28byj-48) with uln2003 controler.
|
Package uln28byj implements a GPIO based stepper motor (model: 28byj-48) with uln2003 controler. |
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.
|
Package adxl345 implements the MovementSensor interface for the ADXL345 accelerometer. |
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/gpsrtkpmtk
Package gpsrtkpmtk implements a gps using serial connection
|
Package gpsrtkpmtk implements a gps using serial connection |
movementsensor/gpsrtkserial
Package gpsrtkserial implements a gps using serial connection
|
Package gpsrtkserial implements a gps using serial connection |
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/merged
Package merged implements a movementsensor combining movement data from other sensors
|
Package merged implements a movementsensor combining movement data from other sensors |
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 |
movementsensor/rtkutils
Package rtkutils defines a gps and an rtk correction source which sends rtcm data to a child gps This is an Experimental package
|
Package rtkutils defines a gps and an rtk correction source which sends rtcm data to a child gps This is an Experimental package |
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 |
powersensor
Package powersensor defines the interfaces of a powersensor
|
Package powersensor defines the interfaces of a powersensor |
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/power_ina219
Package ina219 implements an ina219 voltage/current/power monitor sensor - typically used for battery state monitoring.
|
Package ina219 implements an ina219 voltage/current/power monitor sensor - typically used for battery state monitoring. |
sensor/register
Package register registers all relevant Sensors
|
Package register registers all relevant Sensors |
sensor/sht3xd
Package sht3xd implements a sht3x-d sensor for temperature and humidity datasheet can be found at: https://cdn-shop.adafruit.com/product-files/2857/Sensirion_Humidity_SHT3x_Datasheet_digital-767294.pdf example repo: https://github.com/esphome/esphome/tree/dev/esphome/components/sht3xd
|
Package sht3xd implements a sht3x-d sensor for temperature and humidity datasheet can be found at: https://cdn-shop.adafruit.com/product-files/2857/Sensirion_Humidity_SHT3x_Datasheet_digital-767294.pdf example repo: https://github.com/esphome/esphome/tree/dev/esphome/components/sht3xd |
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. |
testutils
Package testutils helpers for testing the config retrievial.
|
Package testutils helpers for testing the config retrievial. |
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. |
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. |
customresources/apis/gizmoapi
Package gizmoapi implements the acme:component:gizmo API, a demonstraction API showcasing the available GRPC method types.
|
Package gizmoapi implements the acme:component:gizmo API, a demonstraction API showcasing the available GRPC method types. |
customresources/apis/proto/api/component/gizmo/v1
Package v1 is a reverse proxy.
|
Package v1 is a reverse proxy. |
customresources/apis/proto/api/service/summation/v1
Package v1 is a reverse proxy.
|
Package v1 is a reverse proxy. |
customresources/apis/summationapi
Package summationapi defines a simple number summing service API for demonstration purposes.
|
Package summationapi defines a simple number summing service API for demonstration purposes. |
customresources/demos/complexmodule
Package main is a module, which serves all four custom model types in the customresources examples, including both custom APIs.
|
Package main is a module, which serves all four custom model types in the customresources examples, including both custom APIs. |
customresources/demos/complexmodule/client
Package main tests out all four custom models in the complexmodule.
|
Package main tests out all four custom models in the complexmodule. |
customresources/demos/remoteserver
Package main is a standalone server (for use as a remote) serving a demo Gizmo component.
|
Package main is a standalone server (for use as a remote) serving a demo Gizmo component. |
customresources/demos/remoteserver/client
Package main tests out a Gizmo client.
|
Package main tests out a Gizmo client. |
customresources/demos/simplemodule
Package main is a module with a built-in "counter" component model, that will simply track numbers.
|
Package main is a module with a built-in "counter" component model, that will simply track numbers. |
customresources/demos/simplemodule/client
Package main tests out all four custom models in the complexmodule.
|
Package main tests out all four custom models in the complexmodule. |
customresources/models/mybase
Package mybase implements a base that only supports SetPower (basic forward/back/turn controls.)
|
Package mybase implements a base that only supports SetPower (basic forward/back/turn controls.) |
customresources/models/mygizmo
Package mygizmo implements an acme:component:gizmo, a demonstration component that simply shows the various methods available in grpc.
|
Package mygizmo implements an acme:component:gizmo, a demonstration component that simply shows the various methods available in grpc. |
customresources/models/mynavigation
Package mynavigation contains an example navigation service that only stores waypoints, and returns a fixed, configurable location.
|
Package mynavigation contains an example navigation service that only stores waypoints, and returns a fixed, configurable location. |
customresources/models/mysum
Package mysum implements an acme:service:summation, a demo service which sums (or subtracts) a given list of numbers.
|
Package mysum implements an acme:service:summation, a demo service which sums (or subtracts) a given list of numbers. |
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. |
Package internal is used only within this package and all code contained within is not supported and should be considered experimetnal and subject to change.
|
Package internal is used only within this package and all code contained within is not supported and should be considered experimetnal and subject to change. |
cloud
Package cloud implements a service to grab gRPC connections to talk to a cloud service that manages robots.
|
Package cloud implements a service to grab gRPC connections to talk to a cloud service that manages robots. |
testutils/inject
Package inject provides an mock cloud connection service that can be used for testing.
|
Package inject provides an mock cloud connection service that can be used for testing. |
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 module provides services for external resource and logic modules.
|
Package module provides services for external resource and logic modules. |
modmanager
Package modmanager provides the module manager for a robot.
|
Package modmanager provides the module manager for a robot. |
modmanager/options
Package modmanageroptions provides Options for configuring a mod manager
|
Package modmanageroptions provides Options for configuring a mod manager |
modmaninterface
Package modmaninterface abstracts the manager interface to avoid an import cycle/loop.
|
Package modmaninterface abstracts the manager interface to avoid an import cycle/loop. |
testmodule
Package main is a module for testing, with an inline generic component to return internal data and perform other test functions.
|
Package main is a module for testing, with an inline generic component to return internal data and perform other test functions. |
Package motionplan is a motion planning library.
|
Package motionplan is a motion planning library. |
tpspace
Package tpspace defines an assortment of precomputable trajectories which can be used to plan nonholonomic 2d motion
|
Package tpspace defines an assortment of precomputable trajectories which can be used to plan nonholonomic 2d motion |
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 resource contains types that help identify and classify resources (components/services) of a robot.
|
Package resource contains types that help identify and classify resources (components/services) of a robot. |
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 the frame system service which is responsible for managing a stateful frame system
|
Package framesystem defines the frame system service which is responsible for managing a stateful frame system |
impl
Package robotimpl defines implementations of robot.Robot and robot.LocalRobot.
|
Package robotimpl defines implementations of robot.Robot and robot.LocalRobot. |
packages
Package packages contains utilities and manager to sync Viam packages defined in the RDK config from the Viam app to the local robot.
|
Package packages contains utilities and manager to sync Viam packages defined in the RDK config from the Viam app to the local robot. |
packages/testutils
Package testutils is test helpers for packages.
|
Package testutils is test helpers for packages. |
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. |
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
|
|
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 API specific functions
|
Package register registers all relevant baseremotecontrol models and also API 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/register
Package register registers all relevant datamanager models and also API specific functions
|
Package register registers all relevant datamanager models and also API specific functions |
mlmodel
Package mlmodel defines the client and server for a service that can take in a map of input tensors/arrays, pass them through an inference engine, and then return a map output tensors/arrays.
|
Package mlmodel defines the client and server for a service that can take in a map of input tensors/arrays, pass them through an inference engine, and then return a map output tensors/arrays. |
mlmodel/register
Package register registers all relevant ML model services
|
Package register registers all relevant ML model services |
mlmodel/tflitecpu
Package tflitecpu runs tflite model files on the host's CPU, as an implementation the ML model service.
|
Package tflitecpu runs tflite model files on the host's CPU, as an implementation the ML model service. |
motion
Package motion is the service that allows you to plan and execute movements.
|
Package motion is the service that allows you to plan and execute movements. |
motion/builtin
Package builtin implements a motion service.
|
Package builtin implements a motion service. |
motion/register
Package register registers all relevant motion services and API specific functions.
|
Package register registers all relevant motion services and API specific functions. |
navigation
Package navigation is the service that allows you to navigate along waypoints.
|
Package navigation is the service that allows you to navigate along waypoints. |
navigation/builtin
Package builtin implements a navigation service.
|
Package builtin implements a navigation service. |
navigation/register
Package register registers all relevant navigation models and API specific functions.
|
Package register registers all relevant navigation models and API 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 API specific functions
|
Package register registers all relevant sensors models and also API 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 API specific functions
|
Package register registers all relevant shell models and also API specific functions |
slam
Package slam implements simultaneous localization and mapping.
|
Package slam implements simultaneous localization and mapping. |
slam/fake
Package fake implements a fake slam service
|
Package fake implements a fake slam service |
slam/grpchelper
Package grpchelper implements helper functions to be used with slam service grpc clients
|
Package grpchelper implements helper functions to be used with slam service grpc clients |
slam/internal/testhelper
Package testhelper implements a slam service definition with additional exported functions for the purpose of testing
|
Package testhelper 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 API specific functions
|
Package register registers all relevant slam models and also API 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/colordetector
Package colordetector uses a heuristic based on hue and connected components to create bounding boxes around objects of a specified color.
|
Package colordetector uses a heuristic based on hue and connected components to create bounding boxes around objects of a specified color. |
vision/detectionstosegments
Package detectionstosegments uses a 2D segmenter and a camera that can project its images to 3D to project the bounding boxes to 3D in order to created a segmented point cloud.
|
Package detectionstosegments uses a 2D segmenter and a camera that can project its images to 3D to project the bounding boxes to 3D in order to created a segmented point cloud. |
vision/mlvision
Package mlvision uses an underlying model from the ML model service as a vision model, and wraps the ML model with the vision service methods.
|
Package mlvision uses an underlying model from the ML model service as a vision model, and wraps the ML model with the vision service methods. |
vision/obstacledistance
Package obstacledistance uses an underlying camera to fulfill vision service methods, specifically GetObjectPointClouds, which performs several queries of NextPointCloud and returns a median point.
|
Package obstacledistance uses an underlying camera to fulfill vision service methods, specifically GetObjectPointClouds, which performs several queries of NextPointCloud and returns a median point. |
vision/obstaclespointcloud
Package obstaclespointcloud uses the 3D radius clustering algorithm as defined in the RDK vision/segmentation package as vision model.
|
Package obstaclespointcloud uses the 3D radius clustering algorithm as defined in the RDK vision/segmentation package as vision model. |
vision/register
Package register registers all relevant vision models and also API specific functions
|
Package register registers all relevant vision models and also API 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 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 |
vcamera
Package vcamera creates and streams video to virtual V4L2 capture devices on Linux.
|
Package vcamera creates and streams video to virtual V4L2 capture devices on Linux. |
vcamera/cmd
This package creates two virtual cameras and streams test video to them until the program halts (with ctrl-c for example).
|
This package creates two virtual cameras and streams test video to them until the program halts (with ctrl-c for example). |
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. |
contextutils
Package contextutils provides utility for adding and retrieving metadata to/from a context.
|
Package contextutils provides utility for adding and retrieving metadata to/from a context. |
Package vision implements computer vision algorithms.
|
Package vision implements computer vision algorithms. |
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. |
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. |
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. |
Click to show internal directories.
Click to hide internal directories.