RobotLocomotion / drake

Model-based design and verification for robotics.
https://drake.mit.edu
Other
3.25k stars 1.25k forks source link

How to get context from simulator? #8677

Closed Islam0mar closed 6 years ago

Islam0mar commented 6 years ago

I am porting code from python:

from pydrake.all import (BasicVector, DiagramBuilder, FloatingBaseType,
                         RigidBodyPlant, RigidBodyTree, Simulator)
from underactuated import (FindResource, PlanarRigidBodyVisualizer)

# Load the double pendulum from Universal Robot Description Format
tree = RigidBodyTree(FindResource("double_pendulum/double_pendulum.urdf"),
                     FloatingBaseType.kFixed)

# Set up a block diagram with the robot (dynamics) and a visualization block.
builder = DiagramBuilder()
robot = builder.AddSystem(RigidBodyPlant(tree))
builder.ExportInput(robot.get_input_port(0))
visualizer = builder.AddSystem(PlanarRigidBodyVisualizer(tree,
                                                         xlim=[-2.8, 2.8],
                                                         ylim=[-2.8, 2.8]))
builder.Connect(robot.get_output_port(0), visualizer.get_input_port(0))
diagram = builder.Build()

# Set up a simulator to run this diagram
simulator = Simulator(diagram)
simulator.set_target_realtime_rate(1.0)
simulator.set_publish_every_time_step(False)

# Set the initial conditions
context = simulator.get_mutable_context()

here is c++ code:

#include <memory>
#include <gflags/gflags.h>
#include <sys/stat.h>
#include "drake/common/find_resource.h"
#include "drake/common/text_logging_gflags.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/multibody/joints/floating_base_types.h"
#include <drake/multibody/parsers/urdf_parser.h>
#include "drake/multibody/rigid_body_plant/drake_visualizer.h"
#include "drake/multibody/rigid_body_plant/rigid_body_plant.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/diagram.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/primitives/constant_vector_source.h"

#include<iostream>

/// Fixed path to particle URDF model (for visualization purposes only).
static const char* const kPendulumUrdfPath = "double_pendulum.urdf";

/// Check if the specified file exists.
/// @param[in] name of the file
/// @return existence (true) or otherwise (false)
// bool file_exists(const std::string& name) {
//   struct stat buffer;
//   return (stat(name.c_str(), &buffer) == 0);
// }

using namespace drake;

drake::lcm::DrakeLcm lcm_;

auto tree = std::make_unique<RigidBodyTree<double>>();

// if (!file_exists(kPendulumUrdfPath)) {
//   throw std::runtime_error(std::string("could not find '") +
//                            kPendulumUrdfPath + std::string("'"));
// }

parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
    kPendulumUrdfPath, multibody::joints::kFixed, tree.get());

tree->compile();

systems::BasicVector<double> input(2);
input.SetAtIndex(0, 0.0);
input.SetAtIndex(1, 0.0);

// Instantiate builder.
systems::DiagramBuilder<double> builder;

// builder.Connect(source->get_output_port(), pendulum->get_input_port());
// builder.Connect(pendulum->get_output_port(), publisher->get_input_port(0));

// auto source = builder.AddSystem<systems::ConstantVectorSource>(input);

// Move double pendulum tree to plant.
auto plant = builder.AddSystem<systems::RigidBodyPlant<double>>(
    std::move(tree));

builder.ExportInput(plant->get_input_port(0));
// Add visualizer client.
auto visualizer = builder.AddSystem<systems::DrakeVisualizer>(
    plant->get_rigid_body_tree() , &lcm_);

// Wire all blo`cks together.
// builder.Connect(source->get_output_port(0), plant->get_input_port(0));
// builder.Connect(source->get_output_port(1), plant->get_input_port(1));
builder.Connect(plant->get_output_port(0), visualizer->get_input_port(0));

auto diagram = builder.Build();
// Instantiate and configure simulator.

systems::Simulator<double> simulator(*diagram);
// auto simulator = std::make_unique<systems::Simulator<double>>(*diagram);
simulator.set_target_realtime_rate(1.0);
simulator.Initialize();

systems::Context<double> context(simulator.get_mutable_context());

when I do that I get

[cling]$ auto context = simulator.get_context(); input_line_76:2:7: error: variable type 'drake::systems::Context' is an abstract class auto context = simulator.get_context(); ^ [cling]$ auto context = simulator.get_mutable_context(); input_line_77:2:27: error: no member named 'get_mutable_context' in 'drake::systems::Simulator' auto context = simulator.get_mutable_context();

sherm1 commented 6 years ago

In C++ you want:

  Context<double>& context = simulator.get_mutable_context();