Skip to content

Commit

Permalink
Refactored names of task definitions and dynamics to unify naming con…
Browse files Browse the repository at this point in the history
…vention
  • Loading branch information
neckutrek committed Dec 28, 2016
1 parent 62bfbe2 commit 8203605
Show file tree
Hide file tree
Showing 40 changed files with 306 additions and 281 deletions.
22 changes: 12 additions & 10 deletions hiqp_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,16 +52,18 @@ add_library(${PROJECT_NAME} src/utilities.cpp
src/geometric_primitives/geometric_primitive_map.cpp

src/solvers/gurobi_solver.cpp
src/tasks/dynamics_first_order.cpp
src/tasks/dynamics_first_order_cubic.cpp
src/tasks/dynamics_jnt_limits.cpp
src/tasks/dynamics_minimal_jerk.cpp
src/tasks/dynamics_hyper_sin.cpp
src/tasks/task_full_pose.cpp
src/tasks/task_geometric_projection.cpp
src/tasks/task_geometric_alignment.cpp
src/tasks/task_jnt_config.cpp
src/tasks/task_jnt_limits.cpp

src/tasks/tdyn_linear.cpp
src/tasks/tdyn_cubic.cpp
src/tasks/tdyn_hyper_sin.cpp
src/tasks/tdyn_jnt_limits.cpp
src/tasks/tdyn_minimal_jerk.cpp

src/tasks/tdef_full_pose.cpp
src/tasks/tdef_geometric_alignment.cpp
src/tasks/tdef_geometric_projection.cpp
src/tasks/tdef_jnt_config.cpp
src/tasks/tdef_jnt_limits.cpp
)

target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.

#ifndef HIQP_TASK_FULL_POSE_H
#define HIQP_TASK_FULL_POSE_H
#ifndef HIQP_TDEF_FULL_POSE_H
#define HIQP_TDEF_FULL_POSE_H

#include <string>

Expand All @@ -29,15 +29,13 @@ namespace tasks

/*! \brief Represents a task definition that sets a specific joint configuration. This task definition does not leave any redundancy available to other tasks!
* \author Marcus A Johansson */
class TaskFullPose : public TaskDefinition
{
class TDefFullPose : public TaskDefinition {
public:

TaskFullPose(std::shared_ptr<GeometricPrimitiveMap> geom_prim_map,
TDefFullPose(std::shared_ptr<GeometricPrimitiveMap> geom_prim_map,
std::shared_ptr<Visualizer> visualizer)
: TaskDefinition(geom_prim_map, visualizer) {}

~TaskFullPose() noexcept {}
~TDefFullPose() noexcept {}

int init(const std::vector<std::string>& parameters,
RobotStatePtr robot_state);
Expand All @@ -47,10 +45,10 @@ namespace tasks
int monitor();

private:
TaskFullPose(const TaskFullPose& other) = delete;
TaskFullPose(TaskFullPose&& other) = delete;
TaskFullPose& operator=(const TaskFullPose& other) = delete;
TaskFullPose& operator=(TaskFullPose&& other) noexcept = delete;
TDefFullPose(const TDefFullPose& other) = delete;
TDefFullPose(TDefFullPose&& other) = delete;
TDefFullPose& operator=(const TDefFullPose& other) = delete;
TDefFullPose& operator=(TDefFullPose&& other) noexcept = delete;

std::vector<double> desired_configuration_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.

#ifndef HIQP_TASK_GEOMETRIC_ALIGNMENT_H
#define HIQP_TASK_GEOMETRIC_ALIGNMENT_H
#ifndef HIQP_TDEF_GEOMETRIC_ALIGNMENT_H
#define HIQP_TDEF_GEOMETRIC_ALIGNMENT_H

#include <string>
#include <vector>
Expand All @@ -34,11 +34,11 @@ namespace tasks
/*! \brief A task definition that rotates primitives to align with each other.
* \author Marcus A Johansson */
template<typename PrimitiveA, typename PrimitiveB>
class TaskGeometricAlignment : public TaskDefinition {
class TDefGeometricAlignment : public TaskDefinition {
public:
TaskGeometricAlignment(std::shared_ptr<GeometricPrimitiveMap> geom_prim_map,
TDefGeometricAlignment(std::shared_ptr<GeometricPrimitiveMap> geom_prim_map,
std::shared_ptr<Visualizer> visualizer);
~TaskGeometricAlignment() noexcept = default;
~TDefGeometricAlignment() noexcept = default;

int init(const std::vector<std::string>& parameters,
RobotStatePtr robot_state);
Expand All @@ -48,10 +48,10 @@ namespace tasks
int monitor();

private:
TaskGeometricAlignment(const TaskGeometricAlignment& other) = delete;
TaskGeometricAlignment(TaskGeometricAlignment&& other) = delete;
TaskGeometricAlignment& operator=(const TaskGeometricAlignment& other) = delete;
TaskGeometricAlignment& operator=(TaskGeometricAlignment&& other) noexcept = delete;
TDefGeometricAlignment(const TDefGeometricAlignment& other) = delete;
TDefGeometricAlignment(TDefGeometricAlignment&& other) = delete;
TDefGeometricAlignment& operator=(const TDefGeometricAlignment& other) = delete;
TDefGeometricAlignment& operator=(TDefGeometricAlignment&& other) noexcept = delete;

int align(std::shared_ptr<PrimitiveA> first, std::shared_ptr<PrimitiveB> second);
int alignVectors(const KDL::Vector& v1, const KDL::Vector v2);
Expand All @@ -78,6 +78,6 @@ namespace tasks

} // namespace hiqp

#include <hiqp/tasks/task_geometric_alignment__impl.h>
#include <hiqp/tasks/tdef_geometric_alignment__impl.h>

#endif // include guard
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.

#ifndef HIQP_TASK_GEOMETRIC_ALIGNMENT__IMPL_H
#define HIQP_TASK_GEOMETRIC_ALIGNMENT__IMPL_H
#ifndef HIQP_TDEF_GEOMETRIC_ALIGNMENT__IMPL_H
#define HIQP_TDEF_GEOMETRIC_ALIGNMENT__IMPL_H

#include <sstream>
#include <iterator>
Expand All @@ -28,13 +28,13 @@ namespace tasks
{

template<typename PrimitiveA, typename PrimitiveB>
TaskGeometricAlignment<PrimitiveA, PrimitiveB>::TaskGeometricAlignment(
TDefGeometricAlignment<PrimitiveA, PrimitiveB>::TDefGeometricAlignment(
std::shared_ptr<GeometricPrimitiveMap> geom_prim_map,
std::shared_ptr<Visualizer> visualizer)
: TaskDefinition(geom_prim_map, visualizer) {}

template<typename PrimitiveA, typename PrimitiveB>
int TaskGeometricAlignment<PrimitiveA, PrimitiveB>::init(const std::vector<std::string>& parameters,
int TDefGeometricAlignment<PrimitiveA, PrimitiveB>::init(const std::vector<std::string>& parameters,
RobotStatePtr robot_state) {
int parameters_size = parameters.size();
if (parameters_size != 5) {
Expand Down Expand Up @@ -94,12 +94,12 @@ namespace tasks
}

template<typename PrimitiveA, typename PrimitiveB>
int TaskGeometricAlignment<PrimitiveA, PrimitiveB>::update(RobotStatePtr robot_state) {
int TDefGeometricAlignment<PrimitiveA, PrimitiveB>::update(RobotStatePtr robot_state) {
int retval = 0;

retval = fk_solver_pos_->JntToCart(robot_state->kdl_jnt_array_vel_.q, pose_a_, primitive_a_->getFrameId());
if (retval != 0) {
std::cerr << "In TaskGeometricAlignment::apply : Can't solve position "
std::cerr << "In TDefGeometricAlignment::apply : Can't solve position "
<< "of link '" << primitive_a_->getFrameId() << "'" << " in the "
<< "KDL tree! KDL::TreeFkSolverPos_recursive::JntToCart return "
<< "error code '" << retval << "'\n";
Expand All @@ -108,7 +108,7 @@ namespace tasks

retval = fk_solver_pos_->JntToCart(robot_state->kdl_jnt_array_vel_.q, pose_b_, primitive_b_->getFrameId());
if (retval != 0) {
std::cerr << "In TaskGeometricAlignment::apply : Can't solve position "
std::cerr << "In TDefGeometricAlignment::apply : Can't solve position "
<< "of link '" << primitive_b_->getFrameId() << "'" << " in the "
<< "KDL tree! KDL::TreeFkSolverPos_recursive::JntToCart return "
<< "error code '" << retval << "'\n";
Expand All @@ -118,7 +118,7 @@ namespace tasks
jacobian_a_.resize(robot_state->kdl_jnt_array_vel_.q.rows());
retval = fk_solver_jac_->JntToJac(robot_state->kdl_jnt_array_vel_.q, jacobian_a_, primitive_a_->getFrameId());
if (retval != 0) {
std::cerr << "In TaskGeometricAlignment::apply : Can't solve jacobian "
std::cerr << "In TDefGeometricAlignment::apply : Can't solve jacobian "
<< "of link '" << primitive_a_->getFrameId() << "'" << " in the "
<< "KDL tree! KDL::TreeJntToJacSolver return error code "
<< "'" << retval << "'\n";
Expand All @@ -128,7 +128,7 @@ namespace tasks
jacobian_b_.resize(robot_state->kdl_jnt_array_vel_.q.rows());
retval = fk_solver_jac_->JntToJac(robot_state->kdl_jnt_array_vel_.q, jacobian_b_, primitive_b_->getFrameId());
if (retval != 0) {
std::cerr << "In TaskGeometricAlignment::apply : Can't solve jacobian "
std::cerr << "In TDefGeometricAlignment::apply : Can't solve jacobian "
<< "of link '" << primitive_b_->getFrameId() << "'" << " in the "
<< "KDL tree! KDL::TreeJntToJacSolver return error code "
<< "'" << retval << "'\n";
Expand All @@ -141,20 +141,20 @@ namespace tasks
}

template<typename PrimitiveA, typename PrimitiveB>
int TaskGeometricAlignment<PrimitiveA, PrimitiveB>::monitor() {
int TDefGeometricAlignment<PrimitiveA, PrimitiveB>::monitor() {
return 0;
}

template<typename PrimitiveA, typename PrimitiveB>
void TaskGeometricAlignment<PrimitiveA, PrimitiveB>::maskJacobian(RobotStatePtr robot_state) {
void TDefGeometricAlignment<PrimitiveA, PrimitiveB>::maskJacobian(RobotStatePtr robot_state) {
for (unsigned int c=0; c<robot_state->getNumJoints(); ++c) {
if (!robot_state->isQNrWritable(c))
J_.col(c).setZero();
}
}

template<typename PrimitiveA, typename PrimitiveB>
int TaskGeometricAlignment<PrimitiveA, PrimitiveB>::alignVectors
int TDefGeometricAlignment<PrimitiveA, PrimitiveB>::alignVectors
(
const KDL::Vector& v1,
const KDL::Vector v2
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.

#ifndef HIQP_TASK_GEOMETRIC_PROJECTION_H
#define HIQP_TASK_GEOMETRIC_PROJECTION_H
#ifndef HIQP_TDEF_GEOMETRIC_PROJECTION_H
#define HIQP_TDEF_GEOMETRIC_PROJECTION_H

#include <string>
#include <vector>
Expand All @@ -34,11 +34,11 @@ namespace tasks
/*! \brief A task definition that positions geometric primitives relative to each other through mutual geometric projection.
* \author Marcus A Johansson */
template<typename PrimitiveA, typename PrimitiveB>
class TaskGeometricProjection : public TaskDefinition {
class TDefGeometricProjection : public TaskDefinition {
public:
TaskGeometricProjection(std::shared_ptr<GeometricPrimitiveMap> geom_prim_map,
TDefGeometricProjection(std::shared_ptr<GeometricPrimitiveMap> geom_prim_map,
std::shared_ptr<Visualizer> visualizer);
~TaskGeometricProjection() noexcept = default;
~TDefGeometricProjection() noexcept = default;

int init(const std::vector<std::string>& parameters,
RobotStatePtr robot_state);
Expand All @@ -48,10 +48,10 @@ namespace tasks
int monitor();

private:
TaskGeometricProjection(const TaskGeometricProjection& other) = delete;
TaskGeometricProjection(TaskGeometricProjection&& other) = delete;
TaskGeometricProjection& operator=(const TaskGeometricProjection& other) = delete;
TaskGeometricProjection& operator=(TaskGeometricProjection&& other) noexcept = delete;
TDefGeometricProjection(const TDefGeometricProjection& other) = delete;
TDefGeometricProjection(TDefGeometricProjection&& other) = delete;
TDefGeometricProjection& operator=(const TDefGeometricProjection& other) = delete;
TDefGeometricProjection& operator=(TDefGeometricProjection&& other) noexcept = delete;

int project(std::shared_ptr<PrimitiveA> first, std::shared_ptr<PrimitiveB> second);

Expand Down Expand Up @@ -85,6 +85,6 @@ namespace tasks

} // namespace hiqp

#include <hiqp/tasks/task_geometric_projection__impl.h>
#include <hiqp/tasks/tdef_geometric_projection__impl.h>

#endif // include guard
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.

#ifndef HIQP_TASK_GEOMETRIC_PROJECTION__IMPL_H
#define HIQP_TASK_GEOMETRIC_PROJECTION__IMPL_H
#ifndef HIQP_TDEF_GEOMETRIC_PROJECTION__IMPL_H
#define HIQP_TDEF_GEOMETRIC_PROJECTION__IMPL_H

#include <sstream>
#include <iterator>
Expand All @@ -28,14 +28,14 @@ namespace tasks
{

template<typename PrimitiveA, typename PrimitiveB>
TaskGeometricProjection<PrimitiveA, PrimitiveB>::TaskGeometricProjection(
TDefGeometricProjection<PrimitiveA, PrimitiveB>::TDefGeometricProjection(
std::shared_ptr<GeometricPrimitiveMap> geom_prim_map,
std::shared_ptr<Visualizer> visualizer)
: TaskDefinition(geom_prim_map, visualizer) {}


template<typename PrimitiveA, typename PrimitiveB>
int TaskGeometricProjection<PrimitiveA, PrimitiveB>::init(const std::vector<std::string>& parameters,
int TDefGeometricProjection<PrimitiveA, PrimitiveB>::init(const std::vector<std::string>& parameters,
RobotStatePtr robot_state) {
int parameters_size = parameters.size();
if (parameters_size != 4) {
Expand Down Expand Up @@ -72,14 +72,14 @@ namespace tasks

primitive_a_ = gpm->getGeometricPrimitive<PrimitiveA>(args.at(0));
if (primitive_a_ == nullptr) {
printHiqpWarning("In TaskGeometricProjection::init(), couldn't find primitive with name '"
printHiqpWarning("In TDefGeometricProjection::init(), couldn't find primitive with name '"
+ args.at(0) + "'. Unable to create task!");
return -3;
}

primitive_b_ = gpm->getGeometricPrimitive<PrimitiveB>(args.at(2));
if (primitive_b_ == nullptr) {
printHiqpWarning("In TaskGeometricProjection::init(), couldn't find primitive with name '"
printHiqpWarning("In TDefGeometricProjection::init(), couldn't find primitive with name '"
+ args.at(2) + "'. Unable to create task!");
return -3;
}
Expand Down Expand Up @@ -109,12 +109,12 @@ namespace tasks


template<typename PrimitiveA, typename PrimitiveB>
int TaskGeometricProjection<PrimitiveA, PrimitiveB>::update(RobotStatePtr robot_state) {
int TDefGeometricProjection<PrimitiveA, PrimitiveB>::update(RobotStatePtr robot_state) {
int retval = 0;

retval = fk_solver_pos_->JntToCart(robot_state->kdl_jnt_array_vel_.q, pose_a_, primitive_a_->getFrameId());
if (retval != 0) {
std::cerr << "In TaskGeometricProjection::apply : Can't solve position "
std::cerr << "In TDefGeometricProjection::apply : Can't solve position "
<< "of link '" << primitive_a_->getFrameId() << "'" << " in the "
<< "KDL tree! KDL::TreeFkSolverPos_recursive::JntToCart return "
<< "error code '" << retval << "'\n";
Expand All @@ -123,7 +123,7 @@ namespace tasks

retval = fk_solver_pos_->JntToCart(robot_state->kdl_jnt_array_vel_.q, pose_b_, primitive_b_->getFrameId());
if (retval != 0) {
std::cerr << "In TaskGeometricProjection::apply : Can't solve position "
std::cerr << "In TDefGeometricProjection::apply : Can't solve position "
<< "of link '" << primitive_b_->getFrameId() << "'" << " in the "
<< "KDL tree! KDL::TreeFkSolverPos_recursive::JntToCart return "
<< "error code '" << retval << "'\n";
Expand All @@ -133,7 +133,7 @@ namespace tasks
jacobian_a_.resize(robot_state->kdl_jnt_array_vel_.q.rows());
retval = fk_solver_jac_->JntToJac(robot_state->kdl_jnt_array_vel_.q, jacobian_a_, primitive_a_->getFrameId());
if (retval != 0) {
std::cerr << "In TaskGeometricProjection::apply : Can't solve jacobian "
std::cerr << "In TDefGeometricProjection::apply : Can't solve jacobian "
<< "of link '" << primitive_a_->getFrameId() << "'" << " in the "
<< "KDL tree! KDL::TreeJntToJacSolver return error code "
<< "'" << retval << "'\n";
Expand All @@ -143,7 +143,7 @@ namespace tasks
jacobian_b_.resize(robot_state->kdl_jnt_array_vel_.q.rows());
retval = fk_solver_jac_->JntToJac(robot_state->kdl_jnt_array_vel_.q, jacobian_b_, primitive_b_->getFrameId());
if (retval != 0) {
std::cerr << "In TaskGeometricProjection::apply : Can't solve jacobian "
std::cerr << "In TDefGeometricProjection::apply : Can't solve jacobian "
<< "of link '" << primitive_b_->getFrameId() << "'" << " in the "
<< "KDL tree! KDL::TreeJntToJacSolver return error code "
<< "'" << retval << "'\n";
Expand All @@ -156,12 +156,12 @@ namespace tasks
}

template<typename PrimitiveA, typename PrimitiveB>
int TaskGeometricProjection<PrimitiveA, PrimitiveB>::monitor() {
int TDefGeometricProjection<PrimitiveA, PrimitiveB>::monitor() {
return 0;
}

template<typename PrimitiveA, typename PrimitiveB>
KDL::Vector TaskGeometricProjection<PrimitiveA, PrimitiveB>::getVelocityJacobianForTwoPoints(
KDL::Vector TDefGeometricProjection<PrimitiveA, PrimitiveB>::getVelocityJacobianForTwoPoints(
const KDL::Vector& p1,
const KDL::Vector& p2,
int q_nr)
Expand All @@ -175,7 +175,7 @@ namespace tasks
}

template<typename PrimitiveA, typename PrimitiveB>
void TaskGeometricProjection<PrimitiveA, PrimitiveB>::maskJacobian(RobotStatePtr robot_state) {
void TDefGeometricProjection<PrimitiveA, PrimitiveB>::maskJacobian(RobotStatePtr robot_state) {
for (unsigned int c=0; c<robot_state->getNumJoints(); ++c) {
if (!robot_state->isQNrWritable(c))
J_.col(c).setZero();
Expand Down
Loading

0 comments on commit 8203605

Please sign in to comment.