Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_VISUALIZATION_MESHCAT_H_
31 #define EXOTICA_CORE_VISUALIZATION_MESHCAT_H_
52 void Delete(
const std::string& path =
"");
53 void SetProperty(
const std::string& path,
const std::string& property,
const double& value);
54 void SetProperty(
const std::string& path,
const std::string& property,
const std::string& value);
55 void SetProperty(
const std::string& path,
const std::string& property,
const bool& value);
56 void SetProperty(
const std::string& path,
const std::string& property,
const Eigen::Vector3d& value);
57 void SetProperty(
const std::string& path,
const std::string& property,
const Eigen::Vector4d& value);
65 void SendZMQ(
const std::string& data);
83 #endif // EXOTICA_CORE_VISUALIZATION_MESHCAT_H_
std::string RequestWebURL()
void SetProperty(const std::string &path, const std::string &property, const double &value)
std::shared_ptr< Scene > ScenePtr
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
VisualizationMeshcat(ScenePtr scene, const std::string &url, bool use_mesh_materials=true, const std::string &file_url="")
void DisplayTrajectory(Eigen::MatrixXdRefConst trajectory, double dt=1.0)
const typedef Eigen::Ref< const Eigen::MatrixXd > & MatrixXdRefConst
std::unique_ptr< zmq::socket_t > socket_
void DisplayScene(bool use_mesh_materials=true)
void Initialize(bool use_mesh_materials)
virtual ~VisualizationMeshcat()
void SendZMQ(const std::string &data)
void DisplayState(Eigen::VectorXdRefConst state, double t=0.0)
geometry_msgs::TransformStamped t
void Delete(const std::string &path="")
exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02