A Pinocchio robot visualizer. The display() function will perform the draw calls.
More...
#include <candlewick/multibody/Visualizer.h>
|
void | resetCamera () |
|
void | loadViewerModel () override |
|
| Visualizer (const Config &config, const pin::Model &model, const pin::GeometryModel &visual_model, GuiSystem::GuiBehavior gui_callback) |
|
| Visualizer (const Config &config, const pin::Model &model, const pin::GeometryModel &visual_model, pin::Data &data, pin::GeometryData &visual_data, GuiSystem::GuiBehavior callback) |
|
| Visualizer (const Config &config, const pin::Model &model, const pin::GeometryModel &visual_model) |
|
| Visualizer (const Config &config, const pin::Model &model, const pin::GeometryModel &visual_model, pin::Data &data, pin::GeometryData &visual_data) |
|
| ~Visualizer () override |
|
const Device & | device () const |
|
void | setCameraTarget (const Eigen::Ref< const Vector3 > &target) override |
|
void | setCameraPosition (const Eigen::Ref< const Vector3 > &position) override |
|
void | setCameraPose (const Eigen::Ref< const Matrix4 > &pose) override |
|
void | enableCameraControl (bool v) override |
|
void | processEvents () |
|
bool | shouldExit () const noexcept |
|
void | takeScreenshot (std::string_view filename) |
|
void | startRecording (std::string_view filename) |
|
bool | stopRecording () |
| Stop recording the window.
|
|
void | addFrameViz (pin::FrameIndex id, bool show_velocity=true, std::optional< Vector3 > scale=std::nullopt, std::optional< float > vel_scale=std::nullopt) |
| Add visualization for a given frame.
|
|
void | setFrameExternalForce (pin::FrameIndex frame_id, const pin::Force &force, Uint32 lifetime=5u) |
| Add visualization for the body forces expressed at the local frame of a joint.
|
|
void | removeFramesViz () |
| Remove all frame visualizations.
|
|
void | clean () override |
| Clear objects.
|
|
A Pinocchio robot visualizer. The display() function will perform the draw calls.
This visualizer is synchronous. The window is only updated when display()
is called.
◆ Visualizer() [1/4]
candlewick::multibody::Visualizer::Visualizer |
( |
const Config & | config, |
|
|
const pin::Model & | model, |
|
|
const pin::GeometryModel & | visual_model, |
|
|
GuiSystem::GuiBehavior | gui_callback ) |
◆ Visualizer() [2/4]
candlewick::multibody::Visualizer::Visualizer |
( |
const Config & | config, |
|
|
const pin::Model & | model, |
|
|
const pin::GeometryModel & | visual_model, |
|
|
pin::Data & | data, |
|
|
pin::GeometryData & | visual_data, |
|
|
GuiSystem::GuiBehavior | callback ) |
◆ Visualizer() [3/4]
candlewick::multibody::Visualizer::Visualizer |
( |
const Config & | config, |
|
|
const pin::Model & | model, |
|
|
const pin::GeometryModel & | visual_model ) |
|
inline |
◆ Visualizer() [4/4]
candlewick::multibody::Visualizer::Visualizer |
( |
const Config & | config, |
|
|
const pin::Model & | model, |
|
|
const pin::GeometryModel & | visual_model, |
|
|
pin::Data & | data, |
|
|
pin::GeometryData & | visual_data ) |
|
inline |
◆ ~Visualizer()
candlewick::multibody::Visualizer::~Visualizer |
( |
| ) |
|
|
override |
◆ addFrameViz()
void candlewick::multibody::Visualizer::addFrameViz |
( |
pin::FrameIndex | id, |
|
|
bool | show_velocity = true, |
|
|
std::optional< Vector3 > | scale = std::nullopt, |
|
|
std::optional< float > | vel_scale = std::nullopt ) |
Add visualization for a given frame.
- Parameters
-
id | Frame index |
show_velocity | Whether to show frame velocity (as an arrow) |
scale | Assign a scale for the triad (optional, a default value will be assigned instead). |
vel_scale | Velocity arrow scale. |
- Note
- For the velocity to show up, first-order pinocchio::forwardKinematics() must be called with the joint velocity passed in. Since display() with the joint configuration argument
q
calls zeroth-order forward kinematics internally, you should call first-order forward kinematics, then display() without arguments instead.
◆ clean()
void candlewick::multibody::Visualizer::clean |
( |
| ) |
|
|
inlineoverride |
◆ device()
const Device & candlewick::multibody::Visualizer::device |
( |
| ) |
const |
|
inline |
◆ enableCameraControl()
void candlewick::multibody::Visualizer::enableCameraControl |
( |
bool | v | ) |
|
|
inlineoverride |
◆ loadViewerModel()
void candlewick::multibody::Visualizer::loadViewerModel |
( |
| ) |
|
|
override |
◆ processEvents()
void candlewick::multibody::Visualizer::processEvents |
( |
| ) |
|
◆ removeFramesViz()
void candlewick::multibody::Visualizer::removeFramesViz |
( |
| ) |
|
Remove all frame visualizations.
◆ resetCamera()
void candlewick::multibody::Visualizer::resetCamera |
( |
| ) |
|
◆ setCameraPose()
void candlewick::multibody::Visualizer::setCameraPose |
( |
const Eigen::Ref< const Matrix4 > & | pose | ) |
|
|
override |
◆ setCameraPosition()
void candlewick::multibody::Visualizer::setCameraPosition |
( |
const Eigen::Ref< const Vector3 > & | position | ) |
|
|
override |
◆ setCameraTarget()
void candlewick::multibody::Visualizer::setCameraTarget |
( |
const Eigen::Ref< const Vector3 > & | target | ) |
|
|
override |
◆ setFrameExternalForce()
void candlewick::multibody::Visualizer::setFrameExternalForce |
( |
pin::FrameIndex | frame_id, |
|
|
const pin::Force & | force, |
|
|
Uint32 | lifetime = 5u ) |
Add visualization for the body forces expressed at the local frame of a joint.
- Parameters
-
frame_id | Model frame index. |
force | Force value. |
lifetime | Force arrow lifetime. |
◆ shouldExit()
bool candlewick::multibody::Visualizer::shouldExit |
( |
| ) |
const |
|
inlinenodiscardnoexcept |
◆ startRecording()
void candlewick::multibody::Visualizer::startRecording |
( |
std::string_view | filename | ) |
|
◆ stopRecording()
bool candlewick::multibody::Visualizer::stopRecording |
( |
| ) |
|
Stop recording the window.
- Returns
- Whether a recording was actually stopped.
◆ takeScreenshot()
void candlewick::multibody::Visualizer::takeScreenshot |
( |
std::string_view | filename | ) |
|
◆ cameraParams
◆ controller
◆ debugScene
DebugScene candlewick::multibody::Visualizer::debugScene |
◆ DEFAULT_FOV
Radf candlewick::multibody::Visualizer::DEFAULT_FOV = 55.0_degf |
|
staticconstexpr |
◆ guiSystem
GuiSystem candlewick::multibody::Visualizer::guiSystem |
◆ registry
entt::registry candlewick::multibody::Visualizer::registry |
◆ renderer
◆ robotScene
RobotScene candlewick::multibody::Visualizer::robotScene |
◆ show_imgui_about
bool candlewick::multibody::Visualizer::show_imgui_about = false |
◆ show_our_about
bool candlewick::multibody::Visualizer::show_our_about = false |
◆ worldSceneBounds
AABB candlewick::multibody::Visualizer::worldSceneBounds |
The documentation for this class was generated from the following file: