Skip to content

Commit 1fc9e77

Browse files
Update to leverage nested namespaces
1 parent 2de7fa1 commit 1fc9e77

File tree

62 files changed

+981
-973
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

62 files changed

+981
-973
lines changed

tesseract_monitoring/include/tesseract_monitoring/contact_monitor.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,12 +49,12 @@ class ContactMonitor
4949
{
5050
public:
5151
ContactMonitor(std::string monitor_namespace,
52-
std::unique_ptr<tesseract_environment::Environment> env,
52+
std::unique_ptr<tesseract::environment::Environment> env,
5353
ros::NodeHandle& nh,
5454
ros::NodeHandle& pnh,
5555
std::vector<std::string> monitored_link_names,
5656
std::vector<std::string> disabled_link_names,
57-
tesseract_collision::ContactTestType type,
57+
tesseract::collision::ContactTestType type,
5858
double contact_distance = 0.1,
5959
const std::string& joint_state_topic = DEFAULT_JOINT_STATES_TOPIC);
6060
~ContactMonitor();

tesseract_monitoring/include/tesseract_monitoring/current_state_monitor.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -80,14 +80,14 @@ class CurrentStateMonitor
8080
* @param robot_model The current kinematic model to build on
8181
* @param tf A pointer to the tf transformer to use
8282
*/
83-
CurrentStateMonitor(const std::shared_ptr<const tesseract_environment::Environment>& env);
83+
CurrentStateMonitor(const std::shared_ptr<const tesseract::environment::Environment>& env);
8484

8585
/** @brief Constructor.
8686
* @param robot_model The current kinematic model to build on
8787
* @param tf A pointer to the tf transformer to use
8888
* @param nh A ros::NodeHandle to pass node specific options
8989
*/
90-
CurrentStateMonitor(const std::shared_ptr<const tesseract_environment::Environment>& env, const ros::NodeHandle& nh);
90+
CurrentStateMonitor(const std::shared_ptr<const tesseract::environment::Environment>& env, const ros::NodeHandle& nh);
9191

9292
~CurrentStateMonitor();
9393
CurrentStateMonitor(const CurrentStateMonitor&) = delete;
@@ -110,7 +110,7 @@ class CurrentStateMonitor
110110
bool isActive() const;
111111

112112
/** @brief Get the RobotModel for which we are monitoring state */
113-
const tesseract_environment::Environment& getEnvironment() const;
113+
const tesseract::environment::Environment& getEnvironment() const;
114114

115115
/** @brief Get the name of the topic being monitored. Returns an empty string if the monitor is inactive. */
116116
std::string getMonitoredTopic() const;
@@ -141,14 +141,14 @@ class CurrentStateMonitor
141141

142142
/** @brief Get the current state
143143
* @return Returns the current state */
144-
tesseract_scene_graph::SceneState getCurrentState() const;
144+
tesseract::scene_graph::SceneState getCurrentState() const;
145145

146146
/** @brief Get the time stamp for the current state */
147147
ros::Time getCurrentStateTime() const;
148148

149149
/** @brief Get the current state and its time stamp
150150
* @return Returns a pair of the current state and its time stamp */
151-
std::pair<tesseract_scene_graph::SceneState, ros::Time> getCurrentStateAndTime() const;
151+
std::pair<tesseract::scene_graph::SceneState, ros::Time> getCurrentStateAndTime() const;
152152

153153
/** @brief Get the current state values as a map from joint names to joint state values
154154
* @return Returns the map from joint names to joint state values*/

tesseract_monitoring/include/tesseract_monitoring/environment_monitor.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ class CurrentStateMonitor;
5252
/**
5353
* @brief TesseractMonitor
5454
* Subscribes to the topic \e tesseract_environment */
55-
class ROSEnvironmentMonitor : public tesseract_environment::EnvironmentMonitor
55+
class ROSEnvironmentMonitor : public tesseract::environment::EnvironmentMonitor
5656
{
5757
public:
5858
using Ptr = std::shared_ptr<ROSEnvironmentMonitor>;
@@ -72,7 +72,7 @@ class ROSEnvironmentMonitor : public tesseract_environment::EnvironmentMonitor
7272
* @param env The environment
7373
* @param monitor_namespace A name identifying this monitor, must be unique
7474
*/
75-
ROSEnvironmentMonitor(std::shared_ptr<tesseract_environment::Environment> env, std::string monitor_namespace);
75+
ROSEnvironmentMonitor(std::shared_ptr<tesseract::environment::Environment> env, std::string monitor_namespace);
7676

7777
~ROSEnvironmentMonitor() override;
7878
ROSEnvironmentMonitor(const ROSEnvironmentMonitor&) = delete;
@@ -106,8 +106,8 @@ class ROSEnvironmentMonitor : public tesseract_environment::EnvironmentMonitor
106106
void updateEnvironmentWithCurrentState() override final;
107107

108108
void startMonitoringEnvironment(const std::string& monitored_namespace,
109-
tesseract_environment::MonitoredEnvironmentMode mode =
110-
tesseract_environment::MonitoredEnvironmentMode::DEFAULT) override final;
109+
tesseract::environment::MonitoredEnvironmentMode mode =
110+
tesseract::environment::MonitoredEnvironmentMode::DEFAULT) override final;
111111

112112
void stopMonitoringEnvironment() override final;
113113

tesseract_monitoring/include/tesseract_monitoring/environment_monitor_interface.h

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
3434

3535
namespace tesseract_monitoring
3636
{
37-
class ROSEnvironmentMonitorInterface : public tesseract_environment::EnvironmentMonitorInterface
37+
class ROSEnvironmentMonitorInterface : public tesseract::environment::EnvironmentMonitorInterface
3838
{
3939
public:
4040
using Ptr = std::shared_ptr<ROSEnvironmentMonitorInterface>;
@@ -58,52 +58,52 @@ class ROSEnvironmentMonitorInterface : public tesseract_environment::Environment
5858

5959
void removeNamespace(const std::string& monitor_namespace) override final;
6060

61-
std::vector<std::string> applyCommand(const tesseract_environment::Command& command) const override final;
61+
std::vector<std::string> applyCommand(const tesseract::environment::Command& command) const override final;
6262
std::vector<std::string> applyCommands(
63-
const std::vector<std::shared_ptr<const tesseract_environment::Command>>& commands) const override final;
63+
const std::vector<std::shared_ptr<const tesseract::environment::Command>>& commands) const override final;
6464
std::vector<std::string>
65-
applyCommands(const std::vector<tesseract_environment::Command>& commands) const override final;
65+
applyCommands(const std::vector<tesseract::environment::Command>& commands) const override final;
6666

6767
bool applyCommand(const std::string& monitor_namespace,
68-
const tesseract_environment::Command& command) const override final;
68+
const tesseract::environment::Command& command) const override final;
6969
bool applyCommands(
7070
const std::string& monitor_namespace,
71-
const std::vector<std::shared_ptr<const tesseract_environment::Command>>& commands) const override final;
71+
const std::vector<std::shared_ptr<const tesseract::environment::Command>>& commands) const override final;
7272
bool applyCommands(const std::string& monitor_namespace,
73-
const std::vector<tesseract_environment::Command>& commands) const override final;
73+
const std::vector<tesseract::environment::Command>& commands) const override final;
7474

75-
tesseract_scene_graph::SceneState getEnvironmentState(const std::string& monitor_namespace) const override final;
75+
tesseract::scene_graph::SceneState getEnvironmentState(const std::string& monitor_namespace) const override final;
7676

7777
bool setEnvironmentState(const std::string& monitor_namespace,
7878
const std::unordered_map<std::string, double>& joints,
79-
const tesseract_common::TransformMap& floating_joints = {}) const override final;
79+
const tesseract::common::TransformMap& floating_joints = {}) const override final;
8080
bool setEnvironmentState(const std::string& monitor_namespace,
8181
const std::vector<std::string>& joint_names,
8282
const std::vector<double>& joint_values,
83-
const tesseract_common::TransformMap& floating_joints = {}) const override final;
83+
const tesseract::common::TransformMap& floating_joints = {}) const override final;
8484
bool setEnvironmentState(const std::string& monitor_namespace,
8585
const std::vector<std::string>& joint_names,
8686
const Eigen::Ref<const Eigen::VectorXd>& joint_values,
87-
const tesseract_common::TransformMap& floating_joints = {}) const override final;
87+
const tesseract::common::TransformMap& floating_joints = {}) const override final;
8888
bool setEnvironmentState(const std::string& monitor_namespace,
89-
const tesseract_common::TransformMap& floating_joints = {}) const override final;
89+
const tesseract::common::TransformMap& floating_joints = {}) const override final;
9090

9191
std::vector<std::string>
9292
setEnvironmentState(const std::unordered_map<std::string, double>& joints,
93-
const tesseract_common::TransformMap& floating_joints = {}) const override final;
93+
const tesseract::common::TransformMap& floating_joints = {}) const override final;
9494
std::vector<std::string>
9595
setEnvironmentState(const std::vector<std::string>& joint_names,
9696
const std::vector<double>& joint_values,
97-
const tesseract_common::TransformMap& floating_joints = {}) const override final;
97+
const tesseract::common::TransformMap& floating_joints = {}) const override final;
9898
std::vector<std::string>
9999
setEnvironmentState(const std::vector<std::string>& joint_names,
100100
const Eigen::Ref<const Eigen::VectorXd>& joint_values,
101-
const tesseract_common::TransformMap& floating_joints = {}) const override final;
101+
const tesseract::common::TransformMap& floating_joints = {}) const override final;
102102

103103
std::vector<std::string>
104-
setEnvironmentState(const tesseract_common::TransformMap& floating_joints = {}) const override final;
104+
setEnvironmentState(const tesseract::common::TransformMap& floating_joints = {}) const override final;
105105

106-
std::unique_ptr<tesseract_environment::Environment>
106+
std::unique_ptr<tesseract::environment::Environment>
107107
getEnvironment(const std::string& monitor_namespace) const override final;
108108

109109
private:

tesseract_monitoring/src/contact_monitor.cpp

Lines changed: 18 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -58,14 +58,14 @@ struct ContactMonitor::Implementation
5858
std::string monitor_namespace;
5959
std::string monitored_namespace;
6060
int env_revision{ 0 };
61-
tesseract_environment::EnvironmentMonitor::UPtr monitor;
61+
tesseract::environment::EnvironmentMonitor::UPtr monitor;
6262
ros::NodeHandle& nh;
6363
ros::NodeHandle& pnh;
6464
std::vector<std::string> monitored_link_names;
6565
std::vector<std::string> disabled_link_names;
66-
tesseract_collision::ContactTestType type;
66+
tesseract::collision::ContactTestType type;
6767
double contact_distance;
68-
tesseract_collision::DiscreteContactManager::UPtr manager;
68+
tesseract::collision::DiscreteContactManager::UPtr manager;
6969
bool publish_contact_markers{ false };
7070
ros::Subscriber joint_states_sub;
7171
ros::Publisher contact_results_pub;
@@ -76,12 +76,12 @@ struct ContactMonitor::Implementation
7676
std::condition_variable current_joint_states_evt;
7777

7878
Implementation(std::string monitor_namespace_,
79-
tesseract_environment::Environment::UPtr env_,
79+
tesseract::environment::Environment::UPtr env_,
8080
ros::NodeHandle& nh_,
8181
ros::NodeHandle& pnh_,
8282
std::vector<std::string> monitored_link_names_,
8383
std::vector<std::string> disabled_link_names_,
84-
tesseract_collision::ContactTestType type_,
84+
tesseract::collision::ContactTestType type_,
8585
double contact_distance_,
8686
const std::string& joint_state_topic)
8787
: monitor_namespace(std::move(monitor_namespace_))
@@ -128,8 +128,8 @@ struct ContactMonitor::Implementation
128128
while (!ros::isShuttingDown())
129129
{
130130
boost::shared_ptr<sensor_msgs::JointState> msg = nullptr;
131-
tesseract_collision::ContactResultMap contacts;
132-
tesseract_collision::ContactResultVector contacts_vector;
131+
tesseract::collision::ContactResultMap contacts;
132+
tesseract::collision::ContactResultVector contacts_vector;
133133
tesseract_msgs::ContactResultVector contacts_msg;
134134
std::string root_link;
135135
// Limit the lock
@@ -140,8 +140,8 @@ struct ContactMonitor::Implementation
140140
{
141141
// Create a new manager
142142
std::vector<std::string> active;
143-
tesseract_collision::CollisionMarginData contact_margin_data;
144-
tesseract_common::ContactAllowedValidator::ConstPtr fn;
143+
tesseract::collision::CollisionMarginData contact_margin_data;
144+
tesseract::common::ContactAllowedValidator::ConstPtr fn;
145145

146146
{
147147
auto lock_read = monitor->environment().lockRead();
@@ -177,7 +177,7 @@ struct ContactMonitor::Implementation
177177

178178
monitor->environment().setState(msg->name,
179179
Eigen::Map<Eigen::VectorXd>(msg->position.data(), msg->position.size()));
180-
tesseract_scene_graph::SceneState state = monitor->environment().getState();
180+
tesseract::scene_graph::SceneState state = monitor->environment().getState();
181181

182182
manager->setCollisionObjectsTransform(state.link_transforms);
183183
manager->contactTest(contacts, type);
@@ -199,7 +199,7 @@ struct ContactMonitor::Implementation
199199
if (publish_contact_markers)
200200
{
201201
int id_counter = 0;
202-
tesseract_visualization::ContactResultsMarker marker(
202+
tesseract::visualization::ContactResultsMarker marker(
203203
monitored_link_names, contacts_vector, manager->getCollisionMarginData());
204204
visualization_msgs::MarkerArray marker_msg = tesseract_rosutils::getContactResultsMarkerArrayMsg(
205205
id_counter, root_link, "contact_monitor", msg->header.stamp, marker);
@@ -237,8 +237,8 @@ struct ContactMonitor::Implementation
237237

238238
// Create a new manager
239239
std::vector<std::string> active;
240-
tesseract_collision::CollisionMarginData contact_margin_data;
241-
tesseract_common::ContactAllowedValidator::ConstPtr fn;
240+
tesseract::collision::CollisionMarginData contact_margin_data;
241+
tesseract::common::ContactAllowedValidator::ConstPtr fn;
242242

243243
{
244244
auto lock_read = monitor->environment().lockRead();
@@ -260,15 +260,15 @@ struct ContactMonitor::Implementation
260260
bool callbackComputeContactResultVector(tesseract_msgs::ComputeContactResultVectorRequest& request,
261261
tesseract_msgs::ComputeContactResultVectorResponse& response)
262262
{
263-
thread_local tesseract_collision::ContactResultMap contact_results;
264-
thread_local tesseract_collision::ContactResultVector contacts_vector;
263+
thread_local tesseract::collision::ContactResultMap contact_results;
264+
thread_local tesseract::collision::ContactResultVector contacts_vector;
265265
contact_results.clear();
266266
contacts_vector.clear();
267267

268268
monitor->environment().setState(
269269
request.joint_states.name,
270270
Eigen::Map<Eigen::VectorXd>(request.joint_states.position.data(), request.joint_states.position.size()));
271-
tesseract_scene_graph::SceneState state = monitor->environment().getState();
271+
tesseract::scene_graph::SceneState state = monitor->environment().getState();
272272

273273
// Limit the lock
274274
{
@@ -292,12 +292,12 @@ struct ContactMonitor::Implementation
292292
};
293293

294294
ContactMonitor::ContactMonitor(std::string monitor_namespace,
295-
std::unique_ptr<tesseract_environment::Environment> env,
295+
std::unique_ptr<tesseract::environment::Environment> env,
296296
ros::NodeHandle& nh,
297297
ros::NodeHandle& pnh,
298298
std::vector<std::string> monitored_link_names,
299299
std::vector<std::string> disabled_link_names,
300-
tesseract_collision::ContactTestType type,
300+
tesseract::collision::ContactTestType type,
301301
double contact_distance,
302302
const std::string& joint_state_topic)
303303
: impl_(std::make_unique<Implementation>(std::move(monitor_namespace),

tesseract_monitoring/src/contact_monitor_node.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -50,8 +50,8 @@ int main(int argc, char** argv)
5050
ros::NodeHandle nh;
5151
ros::NodeHandle pnh("~");
5252

53-
tesseract_scene_graph::SceneGraph::Ptr scene_graph;
54-
tesseract_srdf::SRDFModel::Ptr srdf_model;
53+
tesseract::scene_graph::SceneGraph::Ptr scene_graph;
54+
tesseract::srdf::SRDFModel::Ptr srdf_model;
5555
std::string robot_description;
5656
std::string joint_state_topic;
5757
std::string monitor_namespace;
@@ -88,8 +88,8 @@ int main(int argc, char** argv)
8888
nh.getParam(robot_description, urdf_xml_string);
8989
nh.getParam(robot_description + "_semantic", srdf_xml_string);
9090

91-
auto env = std::make_unique<tesseract_environment::Environment>();
92-
auto locator = std::make_shared<tesseract_common::GeneralResourceLocator>();
91+
auto env = std::make_unique<tesseract::environment::Environment>();
92+
auto locator = std::make_shared<tesseract::common::GeneralResourceLocator>();
9393
if (!env->init(urdf_xml_string, srdf_xml_string, locator))
9494
{
9595
ROS_ERROR("Failed to initialize environment.");
@@ -158,7 +158,7 @@ int main(int argc, char** argv)
158158
ROS_WARN("Request type must be 0, 1, 2 or 3. Setting to 2(ALL)!");
159159
contact_test_type = 2;
160160
}
161-
tesseract_collision::ContactTestType type = static_cast<tesseract_collision::ContactTestType>(contact_test_type);
161+
tesseract::collision::ContactTestType type = static_cast<tesseract::collision::ContactTestType>(contact_test_type);
162162

163163
tesseract_monitoring::ContactMonitor cm(monitor_namespace,
164164
std::move(env),

0 commit comments

Comments
 (0)