Skip to content

Commit

Permalink
Rename trajopt_utils to trajopt_common
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Jun 30, 2023
1 parent eb9f0b7 commit 052cca8
Show file tree
Hide file tree
Showing 175 changed files with 499 additions and 497 deletions.
2 changes: 1 addition & 1 deletion .run-cpack
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ echo " artifact_dir: $artifact_dir"
echo " artifact_ext: $artifact_ext"
echo " build_dir: $build_dir"

declare -a StringArray=("osqp" "OsqpEigen" "trajopt_utils" "vhacd" "trajopt_sco" "trajopt" "trajopt_sqp" "trajopt_ifopt")
declare -a StringArray=("osqp" "OsqpEigen" "trajopt_common" "vhacd" "trajopt_sco" "trajopt" "trajopt_sqp" "trajopt_ifopt")

# Iterate the packages using for loop
for val in ${StringArray[@]}; do
Expand Down
4 changes: 2 additions & 2 deletions trajopt/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ find_package(Eigen3 REQUIRED)
find_package(Boost REQUIRED)
find_package(console_bridge REQUIRED)
find_package(trajopt_sco REQUIRED)
find_package(trajopt_utils REQUIRED)
find_package(trajopt_common REQUIRED)
find_package(tesseract_common REQUIRED)
find_package(tesseract_environment REQUIRED)
find_package(tesseract_visualization REQUIRED)
Expand Down Expand Up @@ -56,7 +56,7 @@ add_library(${PROJECT_NAME} ${TRAJOPT_SOURCE_FILES})
target_link_libraries(
${PROJECT_NAME}
PUBLIC trajopt::trajopt_sco
trajopt::trajopt_utils
trajopt::trajopt_common
tesseract::tesseract_common
tesseract::tesseract_environment
tesseract::tesseract_visualization
Expand Down
2 changes: 1 addition & 1 deletion trajopt/cmake/trajopt-config.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ else()
endif()
find_dependency(console_bridge)
find_dependency(trajopt_sco)
find_dependency(trajopt_utils)
find_dependency(trajopt_common)
find_dependency(tesseract_environment)
find_dependency(tesseract_visualization)
if(NOT TARGET JsonCpp::JsonCpp)
Expand Down
26 changes: 13 additions & 13 deletions trajopt/include/trajopt/collision_terms.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include <trajopt/cache.hxx>
#include <trajopt/common.hpp>
#include <trajopt_sco/modeling.hpp>
#include <trajopt_utils/utils.hpp>
#include <trajopt_common/utils.hpp>

namespace trajopt
{
Expand Down Expand Up @@ -92,7 +92,7 @@ struct CollisionEvaluator
// NOLINTNEXTLINE
CollisionEvaluator(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
double safety_margin_buffer,
Expand Down Expand Up @@ -208,7 +208,7 @@ struct CollisionEvaluator
* @brief Get the safety margin information.
* @return Safety margin information
*/
util::SafetyMarginData::ConstPtr getSafetyMarginData() const { return safety_margin_data_; }
trajopt_common::SafetyMarginData::ConstPtr getSafetyMarginData() const { return safety_margin_data_; }

/** @brief The collision results cached results */

Expand All @@ -220,7 +220,7 @@ struct CollisionEvaluator
std::vector<std::string> env_active_link_names_;
std::vector<std::string> manip_active_link_names_;
std::vector<std::string> diff_active_link_names_;
util::SafetyMarginData::ConstPtr safety_margin_data_;
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data_;
double safety_margin_buffer_{ 0 };
tesseract_collision::ContactTestType contact_test_type_{ tesseract_collision::ContactTestType::ALL };
double longest_valid_segment_length_{ 0.05 };
Expand Down Expand Up @@ -366,7 +366,7 @@ struct SingleTimestepCollisionEvaluator : public CollisionEvaluator

SingleTimestepCollisionEvaluator(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
sco::VarVector vars,
CollisionExpressionEvaluatorType type,
Expand Down Expand Up @@ -410,7 +410,7 @@ struct CastCollisionEvaluator : public CollisionEvaluator

CastCollisionEvaluator(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
sco::VarVector vars0,
Expand All @@ -431,7 +431,7 @@ struct CastCollisionEvaluator : public CollisionEvaluator
const Eigen::Ref<const Eigen::VectorXd>& dof_vals1,
tesseract_collision::ContactResultMap& dist_results);
void Plot(const tesseract_visualization::Visualization::Ptr& plotter, const DblVec& x) override;
sco::VarVector GetVars() override { return util::concat(vars0_, vars1_); }
sco::VarVector GetVars() override { return trajopt_common::concat(vars0_, vars1_); }

private:
tesseract_collision::ContinuousContactManager::Ptr contact_manager_;
Expand All @@ -450,7 +450,7 @@ struct DiscreteCollisionEvaluator : public CollisionEvaluator

DiscreteCollisionEvaluator(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
sco::VarVector vars0,
Expand All @@ -471,7 +471,7 @@ struct DiscreteCollisionEvaluator : public CollisionEvaluator
const Eigen::Ref<const Eigen::VectorXd>& dof_vals1,
tesseract_collision::ContactResultMap& dist_results);
void Plot(const tesseract_visualization::Visualization::Ptr& plotter, const DblVec& x) override;
sco::VarVector GetVars() override { return util::concat(vars0_, vars1_); }
sco::VarVector GetVars() override { return trajopt_common::concat(vars0_, vars1_); }

private:
tesseract_collision::DiscreteContactManager::Ptr contact_manager_;
Expand All @@ -484,15 +484,15 @@ class CollisionCost : public sco::Cost, public Plotter
/* constructor for single timestep */
CollisionCost(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
sco::VarVector vars,
CollisionExpressionEvaluatorType type,
double safety_margin_buffer);
/* constructor for discrete continuous and cast continuous cost */
CollisionCost(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
sco::VarVector vars0,
Expand All @@ -515,15 +515,15 @@ class CollisionConstraint : public sco::IneqConstraint
/* constructor for single timestep */
CollisionConstraint(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
sco::VarVector vars,
CollisionExpressionEvaluatorType type,
double safety_margin_buffer);
/* constructor for discrete continuous and cast continuous cost */
CollisionConstraint(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
sco::VarVector vars0,
Expand Down
2 changes: 1 addition & 1 deletion trajopt/include/trajopt/json_marshal.hpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#pragma once
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <Eigen/Eigen>
#include <boost/format.hpp>
Expand Down
2 changes: 1 addition & 1 deletion trajopt/include/trajopt/kinematic_terms.hpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#pragma once
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <Eigen/Core>

Expand Down
6 changes: 3 additions & 3 deletions trajopt/include/trajopt/problem_description.hpp
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
#pragma once
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <unordered_map>
TRAJOPT_IGNORE_WARNINGS_POP

#include <tesseract_environment/environment.h>
#include <trajopt/common.hpp>
#include <trajopt_sco/optimizers.hpp>
#include <trajopt_utils/utils.hpp>
#include <trajopt_common/utils.hpp>

namespace sco
{
Expand Down Expand Up @@ -587,7 +587,7 @@ struct CollisionTermInfo : public TermInfo

/** @brief Contains distance penalization data: Safety Margin, Coeff used during */
/** @brief optimization, etc. */
std::vector<util::SafetyMarginData::Ptr> info;
std::vector<trajopt_common::SafetyMarginData::Ptr> info;

/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
Expand Down
2 changes: 1 addition & 1 deletion trajopt/include/trajopt/trajectory_costs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ Simple quadratic costs on trajectory

#include <trajopt/common.hpp>
#include <trajopt_sco/modeling.hpp>
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>

namespace trajopt
{
Expand Down
10 changes: 5 additions & 5 deletions trajopt/include/trajopt/typedefs.hpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#pragma once
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <Eigen/Core>
#include <map>
Expand All @@ -10,13 +10,13 @@ TRAJOPT_IGNORE_WARNINGS_POP

#include <trajopt_sco/modeling.hpp>
#include <trajopt_sco/modeling_utils.hpp>
#include <trajopt_utils/basic_array.hpp>
#include <trajopt_common/basic_array.hpp>

namespace trajopt
{
using VarArray = util::BasicArray<sco::Var>;
using AffArray = util::BasicArray<sco::AffExpr>;
using CntArray = util::BasicArray<sco::Cnt>;
using VarArray = trajopt_common::BasicArray<sco::Var>;
using AffArray = trajopt_common::BasicArray<sco::AffExpr>;
using CntArray = trajopt_common::BasicArray<sco::Cnt>;
using TrajArray = Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>;
using DblVec = sco::DblVec;
using IntVec = sco::IntVec;
Expand Down
2 changes: 1 addition & 1 deletion trajopt/include/trajopt/utils.hpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#pragma once
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <unordered_map>
#include <Eigen/Geometry>
Expand Down
2 changes: 1 addition & 1 deletion trajopt/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
<depend>tesseract_environment</depend>
<depend>tesseract_visualization</depend>
<depend>trajopt_sco</depend>
<depend>trajopt_utils</depend>
<depend>trajopt_common</depend>
<depend>boost</depend>

<test_depend>benchmark</test_depend>
Expand Down
24 changes: 12 additions & 12 deletions trajopt/src/collision_terms.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <boost/functional/hash.hpp>
#include <tesseract_kinematics/core/joint_group.h>
Expand All @@ -13,9 +13,9 @@ TRAJOPT_IGNORE_WARNINGS_POP
#include <trajopt_sco/expr_vec_ops.hpp>
#include <trajopt_sco/modeling_utils.hpp>
#include <trajopt_sco/sco_common.hpp>
#include <trajopt_utils/eigen_conversions.hpp>
#include <trajopt_utils/logging.hpp>
#include <trajopt_utils/stl_to_string.hpp>
#include <trajopt_common/eigen_conversions.hpp>
#include <trajopt_common/logging.hpp>
#include <trajopt_common/stl_to_string.hpp>

namespace trajopt
{
Expand Down Expand Up @@ -549,7 +549,7 @@ void CollisionEvaluator::CollisionsToDistanceExpressionsContinuousW(

CollisionEvaluator::CollisionEvaluator(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
double safety_margin_buffer,
Expand Down Expand Up @@ -865,7 +865,7 @@ void CollisionEvaluator::removeInvalidContactResults(tesseract_collision::Contac
SingleTimestepCollisionEvaluator::SingleTimestepCollisionEvaluator(
tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
sco::VarVector vars,
CollisionExpressionEvaluatorType type,
Expand Down Expand Up @@ -1010,7 +1010,7 @@ void SingleTimestepCollisionEvaluator::Plot(const tesseract_visualization::Visua

DiscreteCollisionEvaluator::DiscreteCollisionEvaluator(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
sco::VarVector vars0,
Expand Down Expand Up @@ -1254,7 +1254,7 @@ void DiscreteCollisionEvaluator::Plot(const tesseract_visualization::Visualizati

CastCollisionEvaluator::CastCollisionEvaluator(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
sco::VarVector vars0,
Expand Down Expand Up @@ -1502,7 +1502,7 @@ void CastCollisionEvaluator::Plot(const tesseract_visualization::Visualization::

CollisionCost::CollisionCost(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
sco::VarVector vars,
CollisionExpressionEvaluatorType type,
Expand All @@ -1520,7 +1520,7 @@ CollisionCost::CollisionCost(tesseract_kinematics::JointGroup::ConstPtr manip,

CollisionCost::CollisionCost(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
sco::VarVector vars0,
Expand Down Expand Up @@ -1609,7 +1609,7 @@ void CollisionCost::Plot(const tesseract_visualization::Visualization::Ptr& plot

CollisionConstraint::CollisionConstraint(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
sco::VarVector vars,
CollisionExpressionEvaluatorType type,
Expand All @@ -1627,7 +1627,7 @@ CollisionConstraint::CollisionConstraint(tesseract_kinematics::JointGroup::Const

CollisionConstraint::CollisionConstraint(tesseract_kinematics::JointGroup::ConstPtr manip,
tesseract_environment::Environment::ConstPtr env,
util::SafetyMarginData::ConstPtr safety_margin_data,
trajopt_common::SafetyMarginData::ConstPtr safety_margin_data,
tesseract_collision::ContactTestType contact_test_type,
double longest_valid_segment_length,
sco::VarVector vars0,
Expand Down
4 changes: 2 additions & 2 deletions trajopt/src/file_write_callback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <functional>
#include <fstream>
Expand All @@ -22,7 +22,7 @@ TRAJOPT_IGNORE_WARNINGS_PUSH
TRAJOPT_IGNORE_WARNINGS_POP

#include <trajopt/file_write_callback.hpp>
#include <trajopt_utils/utils.hpp>
#include <trajopt_common/utils.hpp>

namespace trajopt
{
Expand Down
2 changes: 1 addition & 1 deletion trajopt/src/json_marshal.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include <trajopt_utils/macros.h>
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <json/json.h>
#include <stdexcept>
Expand Down
Loading

0 comments on commit 052cca8

Please sign in to comment.