Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Deprecated entity state() in favor of state_belief() and state_truth() #596

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
124 changes: 62 additions & 62 deletions include/scrimmage/entity/Entity.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,30 +33,29 @@
#ifndef INCLUDE_SCRIMMAGE_ENTITY_ENTITY_H_
#define INCLUDE_SCRIMMAGE_ENTITY_ENTITY_H_

#include <scrimmage/fwd_decl.h>
#include <scrimmage/common/ID.h>
#include <scrimmage/entity/Contact.h>
#include <scrimmage/fwd_decl.h>
#include <scrimmage/proto/Visual.pb.h>
#include <scrimmage/pubsub/Message.h>

#include <boost/optional.hpp>
#include <functional>
#include <list>
#include <map>
#include <memory>
#include <set>
#include <string>
#include <unordered_map>
#include <list>
#include <vector>
#include <string>
#include <functional>
#include <memory>

#include <boost/optional.hpp>

namespace scrimmage_proto {
using ContactVisualPtr = std::shared_ptr<ContactVisual>;
}

namespace scrimmage {

using Service = std::function<bool (scrimmage::MessageBasePtr, scrimmage::MessageBasePtr&)>;
using Service = std::function<bool(scrimmage::MessageBasePtr, scrimmage::MessageBasePtr&)>;

typedef std::map<std::string, std::map<std::string, std::string>> AttributeMap;

Expand All @@ -65,31 +64,22 @@ class Entity : public std::enable_shared_from_this<Entity> {
/*! \name utilities */
///@{

bool init(AttributeMap &overrides,
std::map<std::string, std::string> &info,
std::shared_ptr<std::unordered_map<int, int>> &id_to_team_map,
std::shared_ptr<std::unordered_map<int, EntityPtr>> &id_to_ent_map,
ContactMapPtr &contacts,
MissionParsePtr mp,
const std::shared_ptr<GeographicLib::LocalCartesian> &proj,
int id, int ent_desc_id,
PluginManagerPtr plugin_manager,
FileSearchPtr &file_search,
RTreePtr &rtree,
PubSubPtr &pubsub,
PrintPtr &printer,
TimePtr &time,
const ParameterServerPtr &param_server,
const GlobalServicePtr &global_services,
const std::set<std::string> &plugin_tags,
bool init(AttributeMap& overrides, std::map<std::string, std::string>& info,
std::shared_ptr<std::unordered_map<int, int>>& id_to_team_map,
std::shared_ptr<std::unordered_map<int, EntityPtr>>& id_to_ent_map,
ContactMapPtr& contacts, MissionParsePtr mp,
const std::shared_ptr<GeographicLib::LocalCartesian>& proj, int id, int ent_desc_id,
PluginManagerPtr plugin_manager, FileSearchPtr& file_search, RTreePtr& rtree,
PubSubPtr& pubsub, PrintPtr& printer, TimePtr& time,
const ParameterServerPtr& param_server, const GlobalServicePtr& global_services,
const std::set<std::string>& plugin_tags,
std::function<void(std::map<std::string, std::string>&)> param_override_func,
const int& debug_level = 0);

void print_plugins(std::ostream &out) const;
void print_plugins(std::ostream& out) const;

bool parse_visual(std::map<std::string, std::string> &info,
MissionParsePtr mp,
std::map<std::string, std::string> &overrides);
bool parse_visual(std::map<std::string, std::string>& info, MissionParsePtr mp,
std::map<std::string, std::string>& overrides);

void close(double t);
void collision();
Expand All @@ -100,15 +90,15 @@ class Entity : public std::enable_shared_from_this<Entity> {
void setup_desired_state();
bool ready();

bool call_service(MessageBasePtr req, MessageBasePtr &res, const std::string &service_name);
bool call_service(MessageBasePtr req, MessageBasePtr& res, const std::string& service_name);

bool call_service(MessageBasePtr &res, const std::string &service_name) {
bool call_service(MessageBasePtr& res, const std::string& service_name) {
return call_service(std::make_shared<MessageBase>(), res, service_name);
}

template <class T = MessageBasePtr,
class = typename std::enable_if<!std::is_same<T, MessageBasePtr>::value, void>::type>
bool call_service(MessageBasePtr req, T &res, const std::string &service_name) {
bool call_service(MessageBasePtr req, T& res, const std::string& service_name) {
MessageBasePtr res_base;
if (call_service(req, res_base, service_name)) {
res = std::dynamic_pointer_cast<typename T::element_type>(res_base);
Expand All @@ -125,27 +115,32 @@ class Entity : public std::enable_shared_from_this<Entity> {

template <class T = MessageBasePtr,
class = typename std::enable_if<!std::is_same<T, MessageBasePtr>::value, void>::type>
bool call_service(T &res, const std::string &service_name) {
bool call_service(T& res, const std::string& service_name) {
return call_service(std::make_shared<MessageBase>(), res, service_name);
}
///@}

/*! \name getters/setters */
///@{
StatePtr &state();
StatePtr &state_truth();
std::vector<AutonomyPtr> &autonomies();
MotionModelPtr &motion();
std::vector<ControllerPtr> &controllers();
[[deprecated("Use state_belief() or state_truth() to query state information instead")]]
StatePtr& state();

void set_id(ID &id);
ID &id();
void set_state_belief(const StatePtr& other);
void set_state_belief(const State& other);
const std::shared_ptr<const State> state_belief() const;
StatePtr& state_truth();
std::vector<AutonomyPtr>& autonomies();
MotionModelPtr& motion();
std::vector<ControllerPtr>& controllers();

void set_id(ID& id);
ID& id();

void set_health_points(int health_points);
int health_points();

std::shared_ptr<GeographicLib::LocalCartesian> projection();
void set_projection(const std::shared_ptr<GeographicLib::LocalCartesian> &proj);
void set_projection(const std::shared_ptr<GeographicLib::LocalCartesian>& proj);

void set_mp(MissionParsePtr mp);
MissionParsePtr mp();
Expand All @@ -158,48 +153,54 @@ class Entity : public std::enable_shared_from_this<Entity> {
void set_visual_changed(bool visual_changed);
bool visual_changed();

scrimmage_proto::ContactVisualPtr &contact_visual();
scrimmage_proto::ContactVisualPtr& contact_visual();

std::unordered_map<std::string, SensorPtr> &sensors();
std::unordered_map<std::string, SensorPtr> sensors(const std::string &sensor_name);
SensorPtr sensor(const std::string &sensor_name);
std::unordered_map<std::string, SensorPtr>& sensors();
std::unordered_map<std::string, SensorPtr> sensors(const std::string& sensor_name);
SensorPtr sensor(const std::string& sensor_name);

// Enables creating services at the entity level
std::unordered_map<std::string, Service> &services();
std::unordered_map<std::string, Service>& services();
// Enables creating services at the global level (especially for entity interactions, etc.)
std::unordered_map<std::string, Service> &global_services();
std::unordered_map<std::string, Service>& global_services();
// Enables setting these for entity interactions
void set_global_services(const GlobalServicePtr &global_services);
void set_global_services(const GlobalServicePtr& global_services);

std::unordered_map<std::string, MessageBasePtr> &properties();
std::unordered_map<std::string, MessageBasePtr>& properties();

void set_active(bool active);
bool active();

ContactMapPtr &contacts() { return contacts_; }
RTreePtr &rtree() { return rtree_; }
ContactMapPtr& contacts() {
return contacts_;
}
RTreePtr& rtree() {
return rtree_;
}

PluginManagerPtr & plugin_manager() {
PluginManagerPtr& plugin_manager() {
return plugin_manager_;
}

FileSearchPtr & file_search() {
FileSearchPtr& file_search() {
return file_search_;
}

PubSubPtr & pubsub() {
PubSubPtr& pubsub() {
return pubsub_;
}

PrintPtr & printer() {
PrintPtr& printer() {
return printer_;
}

const ParameterServerPtr& param_server() {
return param_server_;
}

double radius() { return radius_; }
double radius() {
return radius_;
}
void set_time_ptr(TimePtr t);
void set_printer(PrintPtr printer);

Expand All @@ -208,8 +209,7 @@ class Entity : public std::enable_shared_from_this<Entity> {
protected:
ID id_;

scrimmage_proto::ContactVisualPtr visual_ =
std::make_shared<scrimmage_proto::ContactVisual>();
scrimmage_proto::ContactVisualPtr visual_ = std::make_shared<scrimmage_proto::ContactVisual>();

std::vector<ControllerPtr> controllers_;
MotionModelPtr motion_model_;
Expand All @@ -226,7 +226,7 @@ class Entity : public std::enable_shared_from_this<Entity> {

RandomPtr random_;

StatePtr state_;
StatePtr state_belief_;
StatePtr state_truth_;
std::unordered_map<std::string, MessageBasePtr> properties_;
std::unordered_map<std::string, SensorPtr> sensors_;
Expand All @@ -240,7 +240,7 @@ class Entity : public std::enable_shared_from_this<Entity> {

double radius_ = 1;

void print(const std::string &msg);
void print(const std::string& msg);
PluginManagerPtr plugin_manager_;
FileSearchPtr file_search_;
PubSubPtr pubsub_;
Expand All @@ -251,5 +251,5 @@ class Entity : public std::enable_shared_from_this<Entity> {
};

using EntityPtr = std::shared_ptr<Entity>;
} // namespace scrimmage
#endif // INCLUDE_SCRIMMAGE_ENTITY_ENTITY_H_
} // namespace scrimmage
#endif // INCLUDE_SCRIMMAGE_ENTITY_ENTITY_H_
1 change: 1 addition & 0 deletions include/scrimmage/math/State.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ class State {
State();
State(Eigen::Vector3d _pos, Eigen::Vector3d _vel,
Eigen::Vector3d _ang_vel, Quaternion _quat);
State(const State& other);

virtual ~State();

Expand Down
2 changes: 1 addition & 1 deletion python/scrimmage/bindings_src/src/py_openai_env.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ void ScrimmageOpenAIEnv::scrimmage_memory_cleanup() {
e->motion() = nullptr;
e->controllers().clear();
e->set_mp(nullptr);
e->state() = nullptr;
e->state_truth() = nullptr;
e->contacts() = nullptr;
e->plugin_manager() = nullptr;
e->file_search() = nullptr;
Expand Down
Loading