I have been trying to use the C++ API of drake and the following is what I am trying to do.
- Create a multibody plant and scene graph of the robot.
- Create very simple geometries as part of the environment around the robot.
- Solve a very simple Kinematic Trajectory Optimization problem
- Finally visualise the trajectory and the corresponding kinematics of the robot stepping through this trajectory.
I see that there are two ways to visualise this, one is by instantiating meshcat and using the MeshcatVisualizer, something like the following (based on PublishTrajectory
python script):
// also perform some drake related initialisations here
DiagramBuilder<double> builder;
// meshcat experiment
meshcat_params = MeshcatParams();
meshcat = Meshcat(meshcat_params);
std::tie(plant_, scene_graph_) = AddMultibodyPlantSceneGraph(&builder, 0.0);
const char* ModelUrl =
"package://drake_models/franka_description/"
"urdf/panda_arm.urdf";
const std::string urdf = PackageMap{}.ResolveUrl(ModelUrl);
auto robot_instance = Parser(plant_, scene_graph_).AddModels(urdf);
plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("panda_link0"));
// for now finalize plant here
plant_->Finalize();
auto diagram_ = builder.Build();
diagram_context_ = diagram_->CreateDefaultContext();
plant_context_ = &diagram_->GetMutableSubsystemContext(
*plant_,
diagram_context_.get());
visualizer_context_ = &diagram_->GetMutableSubsystemContext(
*visualizer_,
diagram_context_.get());
// do the Kinematic Trajectory Optimization and get the results, store the results in traj
// initialize drake visualizer
visualizer_->StartRecording();
for (double t = 0.0; t <= traj.end_time(); t += time_step)
{
const auto pos_val = traj.value(t);
const auto vel_val = traj.EvalDerivative(t);
const auto waypoint = std::make_shared<moveit::core::RobotState>(start_state);
setJointPositions(pos_val, active_joints, *waypoint);
setJointVelocities(vel_val, active_joints, *waypoint);
res.trajectory->addSuffixWayPoint(waypoint, time_step);
// also try and visualise on drake's visualizer
diagram_context_->SetTime(t);
plant_->SetPositions(plant_context_, pos_val);
visualizer_->ForcedPublish(*visualizer_context_);
}
visualizer_->StopRecording();
visualizer_->PublishRecording();
Use DrakeVisualizer
or use the AddDefaultVisualizer
to be used in combination with the meldis visualization tool, in which case there is no concept of recording and publishing the trajectory (not in the API). I assume this is because the internal LcmPublisher
already publishes relevant geometry.
I could not get either option working and was hoping if there is any example that could point me in the direction of visualising the trajectory. I’d like to be able to visualise the trajectory without specifically simulating the robot.
Thanks for your instruction.