Skip to content

Commit

Permalink
make everything a hpp
Browse files Browse the repository at this point in the history
  • Loading branch information
Flova committed Jan 19, 2024
1 parent a560e01 commit 476e75e
Show file tree
Hide file tree
Showing 66 changed files with 669 additions and 760 deletions.
Original file line number Diff line number Diff line change
@@ -1,19 +1,20 @@
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/char.hpp>
#include <rot_conv/rot_conv.h>
#include <tf2/utils.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_broadcaster.h>

#include <rcl_interfaces/msg/parameter_descriptor.hpp>
#include <tf2_ros/buffer.h>
#include <tf2/utils.h>
#include <rot_conv/rot_conv.h>
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>

#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/char.hpp>
#include <utility>
using std::placeholders::_1;

class ExtrinsicCalibrationBroadcaster : public rclcpp::Node {
public:
ExtrinsicCalibrationBroadcaster();
void step();

private:
OnSetParametersCallbackHandle::SharedPtr param_callback_handle_;
std::unique_ptr<tf2_ros::TransformBroadcaster> broadcaster_;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include <extrinsic_calibration/extrinsic_calibration.h>
#include <extrinsic_calibration/extrinsic_calibration.hpp>

ExtrinsicCalibrationBroadcaster::ExtrinsicCalibrationBroadcaster() : Node("bitbots_extrinsic_calibration") {
broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(this);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,19 +1,21 @@
#ifndef BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_ENGINE_H_
#define BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_ENGINE_H_

#include <cmath>
#include <optional>
#include <Eigen/Geometry>
#include <rot_conv/rot_conv.h>
#include <bitbots_splines/pose_spline.h>
#include <bitbots_splines/position_spline.h>
#include <bitbots_splines/abstract_engine.h>
#include <tf2/convert.h>
#include <tf2/exceptions.h>
#include <tf2/utils.h>

#include <Eigen/Geometry>
#include <bitbots_msgs/action/kick.hpp>
#include <bitbots_splines/abstract_engine.hpp>
#include <bitbots_splines/pose_spline.hpp>
#include <bitbots_splines/position_spline.hpp>
#include <cmath>
#include <optional>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2/convert.h>
#include <tf2/utils.h>
#include <tf2/exceptions.h>

#include "stabilizer.h"
#include "visualizer.h"

Expand Down Expand Up @@ -69,7 +71,7 @@ class PhaseTimings {
*/
class KickEngine : public bitbots_splines::AbstractEngine<KickGoals, KickPositions> {
public:
KickEngine(rclcpp::Node::SharedPtr node);
explicit KickEngine(rclcpp::Node::SharedPtr node);

/**
* Set new goal which the engine tries to kick at. This will remove the old goal completely and plan new splines.
Expand Down Expand Up @@ -167,8 +169,7 @@ class KickEngine : public bitbots_splines::AbstractEngine<KickGoals, KickPositio
*
* @throws tf2::TransformException when ball_position and kick_direction cannot be converted into base_footprint frame
*/
bool calcIsLeftFootKicking(const Eigen::Vector3d &ball_position,
const Eigen::Quaterniond &kick_direction);
bool calcIsLeftFootKicking(const Eigen::Vector3d &ball_position, const Eigen::Quaterniond &kick_direction);

/**
* Calculate the yaw of the kicking foot, so that it is turned
Expand All @@ -186,12 +187,11 @@ class KickEngine : public bitbots_splines::AbstractEngine<KickGoals, KickPositio
*
* @throws tf2::TransformException when goal cannot be transformed into support_foot_frame
*/
std::pair<Eigen::Vector3d, Eigen::Quaterniond> transformGoal(
const std::string &support_foot_frame,
const Eigen::Isometry3d &trunk_to_base_footprint,
const Eigen::Vector3d &ball_position,
const Eigen::Quaterniond &kick_direction);
std::pair<Eigen::Vector3d, Eigen::Quaterniond> transformGoal(const std::string &support_foot_frame,
const Eigen::Isometry3d &trunk_to_base_footprint,
const Eigen::Vector3d &ball_position,
const Eigen::Quaterniond &kick_direction);
};
}
} // namespace bitbots_dynamic_kick

#endif //BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_ENGINE_H_
#endif // BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_ENGINE_H_
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
#ifndef BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_IK_H_
#define BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_IK_H_

#include <Eigen/Geometry>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/planning_scene/planning_scene.h>
#include <bitbots_splines/abstract_ik.h>
#include <bitbots_dynamic_kick/kick_utils.h>
#include <moveit/robot_model_loader/robot_model_loader.h>

#include <Eigen/Geometry>
#include <bitbots_dynamic_kick/kick_utils.hpp>
#include <bitbots_splines/abstract_ik.hpp>

namespace bitbots_dynamic_kick {

Expand All @@ -23,6 +24,6 @@ class KickIK : public bitbots_splines::AbstractIK<KickPositions> {
moveit::core::JointModelGroup *left_leg_joints_group_;
moveit::core::JointModelGroup *right_leg_joints_group_;
};
}
} // namespace bitbots_dynamic_kick

#endif //BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_IK_H_
#endif // BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_IK_H_
Original file line number Diff line number Diff line change
@@ -1,26 +1,26 @@
#ifndef BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_NODE_H_
#define BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_NODE_H_

#include <string>
#include <optional>
#include <Eigen/Geometry>
#include <rclcpp/rclcpp.hpp>
#include <tf2/convert.h>
#include <unistd.h>

#include <rclcpp_action/rclcpp_action.hpp>
#include <Eigen/Geometry>
#include <biped_interfaces/msg/phase.hpp>
#include <bitbots_dynamic_kick/kick_engine.hpp>
#include <bitbots_dynamic_kick/kick_ik.hpp>
#include <bitbots_dynamic_kick/kick_utils.hpp>
#include <bitbots_dynamic_kick/visualizer.hpp>
#include <bitbots_msgs/action/kick.hpp>
#include <bitbots_msgs/msg/joint_command.hpp>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <optional>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <std_msgs/msg/char.hpp>
#include <string>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2/convert.h>
#include <bitbots_msgs/action/kick.hpp>
#include <bitbots_msgs/msg/joint_command.hpp>
#include <bitbots_dynamic_kick/kick_engine.h>
#include <bitbots_dynamic_kick/visualizer.h>
#include <bitbots_dynamic_kick/kick_ik.h>
#include <bitbots_dynamic_kick/kick_utils.h>
#include <biped_interfaces/msg/phase.hpp>
#include <unistd.h>

namespace bitbots_dynamic_kick {
using KickGoal = bitbots_msgs::action::Kick;
Expand All @@ -36,7 +36,7 @@ using namespace std::placeholders;
*
* Additionally it publishes the KickEngines motor-goals back into ROS
*/
class KickNode : public rclcpp::Node{
class KickNode : public rclcpp::Node {
public:
explicit KickNode(const std::string &ns = std::string(), std::vector<rclcpp::Parameter> parameters = {});

Expand Down Expand Up @@ -109,23 +109,23 @@ class KickNode : public rclcpp::Node{
KickParams normal_config_;

/**
* Do main loop in which KickEngine::update() gets called repeatedly.
* The ActionServer's state is taken into account meaning that a cancelled goal no longer gets processed.
*/
* Do main loop in which KickEngine::update() gets called repeatedly.
* The ActionServer's state is taken into account meaning that a cancelled goal no longer gets processed.
*/
void loopEngine(const std::shared_ptr<rclcpp_action::ServerGoalHandle<bitbots_msgs::action::Kick>> goal_handle);

rclcpp_action::GoalResponse goalCb(const rclcpp_action::GoalUUID &uuid,
std::shared_ptr<const bitbots_msgs::action::Kick::Goal> goal);

rclcpp_action::CancelResponse
cancelCb(std::shared_ptr<rclcpp_action::ServerGoalHandle<bitbots_msgs::action::Kick>> goal);
rclcpp_action::CancelResponse cancelCb(
std::shared_ptr<rclcpp_action::ServerGoalHandle<bitbots_msgs::action::Kick>> goal);

void acceptedCb(const std::shared_ptr<KickGoalHandle> goal);

/**
* Execute one step of engine-stabilize-ik
* @return the motor goals
*/
* Execute one step of engine-stabilize-ik
* @return the motor goals
*/
bitbots_splines::JointGoals kickStep(double dt);

/**
Expand All @@ -145,6 +145,6 @@ class KickNode : public rclcpp::Node{

rcl_interfaces::msg::SetParametersResult onSetParameters(const std::vector<rclcpp::Parameter> &parameters);
};
}
} // namespace bitbots_dynamic_kick

#endif //BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_NODE_H_
#endif // BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_NODE_H_
Original file line number Diff line number Diff line change
@@ -1,29 +1,30 @@
#ifndef BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_PYWRAPPER_H_
#define BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_PYWRAPPER_H_

#include <iostream>
#include <map>
#include <Python.h>
#include <moveit/py_bindings_tools/serialize_msg.h>

#include <Eigen/Geometry>
#include <bitbots_dynamic_kick/kick_node.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <iostream>
#include <map>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <moveit/py_bindings_tools/serialize_msg.h>
#include <bitbots_dynamic_kick/kick_node.h>

class PyKickWrapper {
public:
explicit PyKickWrapper(std::string ns);
moveit::py_bindings_tools::ByteString step(double dt, const std::string &joint_state_str);
bool set_goal(const std::string &goal_str, const std::string &joint_state_str);
double get_progress();
//todo
// void set_params(boost::python::object params);
// todo
// void set_params(boost::python::object params);
moveit::py_bindings_tools::ByteString get_trunk_pose();
bool is_left_kick();

private:
std::shared_ptr<bitbots_dynamic_kick::KickNode> kick_node_;
};

#endif //BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_PYWRAPPER_H_
#endif // BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_PYWRAPPER_H_
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,6 @@ enum KickPhase {
DONE = bitbots_dynamic_kick::msg::KickDebug::DONE
};

}
} // namespace bitbots_dynamic_kick

#endif //BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_UTILS_H_
#endif // BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_KICK_UTILS_H_
Original file line number Diff line number Diff line change
@@ -1,21 +1,22 @@
#ifndef BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_STABILIZER_H_
#define BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_STABILIZER_H_

#include <optional>
#include <moveit/robot_state/robot_state.h>
#include <geometry_msgs/msg/pose.hpp>
#include <tf2_ros/transform_listener.h>
#include <bitbots_splines/abstract_stabilizer.h>

#include <bitbots_splines/abstract_stabilizer.hpp>
#include <control_toolbox/pid_ros.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <optional>

#include "kick_utils.h"
#include "visualizer.h"
#include <control_toolbox/pid_ros.hpp>

namespace bitbots_dynamic_kick {

class Stabilizer :
public bitbots_splines::AbstractStabilizer<KickPositions> {
class Stabilizer : public bitbots_splines::AbstractStabilizer<KickPositions> {
public:
Stabilizer(std::string ns);
explicit Stabilizer(std::string ns);

geometry_msgs::msg::Point cop_left;
geometry_msgs::msg::Point cop_right;
Expand All @@ -30,6 +31,7 @@ class Stabilizer :
void reset() override;
void useCop(bool use);
void setRobotModel(moveit::core::RobotModelPtr model);

private:
moveit::core::RobotModelPtr kinematic_model_;
std::shared_ptr<control_toolbox::PidROS> pid_trunk_fused_pitch_;
Expand All @@ -39,6 +41,6 @@ class Stabilizer :

bool use_cop_;
};
}
} // namespace bitbots_dynamic_kick

#endif //BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_STABILIZER_H_
#endif // BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_STABILIZER_H_
Original file line number Diff line number Diff line change
Expand Up @@ -5,20 +5,21 @@
#ifndef BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_VISUALIZER_H_
#define BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_VISUALIZER_H_

#include <bitbots_msgs/action/kick.hpp>
#include <string>
#include <rclcpp/rclcpp.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <bitbots_splines/smooth_spline.h>
#include <bitbots_splines/spline_container.h>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <moveit/robot_state/robot_state.h>
#include <tf2/LinearMath/Vector3.h>
#include <tf2/convert.h>
#include <tf2_eigen/tf2_eigen.hpp>
#include <bitbots_splines/abstract_visualizer.h>
#include <bitbots_dynamic_kick/kick_utils.h>

#include <bitbots_dynamic_kick/kick_utils.hpp>
#include <bitbots_dynamic_kick/msg/kick_debug.hpp>
#include <bitbots_msgs/action/kick.hpp>
#include <bitbots_splines/abstract_visualizer.hpp>
#include <bitbots_splines/smooth_spline.hpp>
#include <bitbots_splines/spline_container.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <tf2_eigen/tf2_eigen.hpp>
#include <visualization_msgs/msg/marker.hpp>

namespace bitbots_dynamic_kick {

Expand All @@ -34,7 +35,6 @@ struct VisualizationParams {

class Visualizer : bitbots_splines::AbstractVisualizer {
public:

explicit Visualizer(const std::string &base_topic, rclcpp::Node::SharedPtr node);

void setParams(VisualizationParams params);
Expand All @@ -47,10 +47,8 @@ class Visualizer : bitbots_splines::AbstractVisualizer {

void displayWindupPoint(const Eigen::Vector3d &kick_windup_point, const std::string &support_foot_frame);

void publishGoals(const KickPositions &positions,
const KickPositions &stabilized_positions,
const moveit::core::RobotStatePtr &robot_state,
KickPhase engine_phase);
void publishGoals(const KickPositions &positions, const KickPositions &stabilized_positions,
const moveit::core::RobotStatePtr &robot_state, KickPhase engine_phase);

private:
rclcpp::Node::SharedPtr node_;
Expand All @@ -63,6 +61,6 @@ class Visualizer : bitbots_splines::AbstractVisualizer {
const std::string marker_ns_ = "bitbots_dynamic_kick";
VisualizationParams params_;
};
}
} // namespace bitbots_dynamic_kick

#endif //BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_VISUALIZER_H_
#endif // BITBOTS_DYNAMIC_KICK_INCLUDE_BITBOTS_DYNAMIC_KICK_VISUALIZER_H_
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_dynamic_kick/src/kick_engine.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "bitbots_dynamic_kick/kick_engine.h"
#include "bitbots_dynamic_kick/kick_engine.hpp"

#include <utility>

Expand Down
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_dynamic_kick/src/kick_ik.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "bitbots_dynamic_kick/kick_ik.h"
#include "bitbots_dynamic_kick/kick_ik.hpp"

namespace bitbots_dynamic_kick {

Expand Down
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_dynamic_kick/src/kick_node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "bitbots_dynamic_kick/kick_node.h"
#include "bitbots_dynamic_kick/kick_node.hpp"

namespace bitbots_dynamic_kick {
using namespace std::chrono_literals;
Expand Down
Loading

0 comments on commit 476e75e

Please sign in to comment.