controller_interface
effort_controllers
geometry_msgs
- message_generation
- message_runtime
nav_msgs
roscpp
tf
+ nonsmooth_backstep_controller_msgs
)
## System dependencies are found with CMake's conventions
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
-add_message_files(
- FILES
+# add_message_files(
+# FILES
# Message1.msg
# Message2.msg
- NonSmoothBackstepControllerStatus.msg
- PosePolar.msg
-)
+# )
## Generate services in the 'srv' folder
# add_service_files(
# )
## Generate added messages and services with any dependencies listed here
-generate_messages(
- DEPENDENCIES
- std_msgs
- geometry_msgs
- nav_msgs
-)
+# generate_messages(
+# DEPENDENCIES
+# std_msgs
+# geometry_msgs
+# nav_msgs
+#)
################################################
## Declare ROS dynamic reconfigure parameters ##
catkin_package(
INCLUDE_DIRS include
LIBRARIES nonsmooth_backstep_controller
- CATKIN_DEPENDS arc_odometry controller_interface effort_controllers geometry_msgs nav_msgs roscpp tf
+ CATKIN_DEPENDS arc_odometry controller_interface effort_controllers geometry_msgs nav_msgs roscpp tf nonsmooth_backstep_controller_msgs
DEPENDS EIGEN3
)
#include <realtime_tools/realtime_publisher.h>
#include <arc_odometry/diff_odometry.h>
-#include <nonsmooth_backstep_controller/NonSmoothBackstepControllerStatus.h>
+#include <nonsmooth_backstep_controller_msgs/NonSmoothBackstepControllerStatus.h>
namespace effort_controllers
{
std::vector<hardware_interface::JointHandle> joints_;
boost::scoped_ptr<realtime_tools::RealtimePublisher
- <nonsmooth_backstep_controller::NonSmoothBackstepControllerStatus>
+ <nonsmooth_backstep_controller_msgs::NonSmoothBackstepControllerStatus>
> status_publisher_ ;
boost::shared_ptr<realtime_tools::RealtimePublisher
+++ /dev/null
-Header header
-geometry_msgs/Pose2D set_point
-geometry_msgs/Pose2D process_value
-geometry_msgs/Pose2D process_value_dot
-geometry_msgs/Pose2D error
-float64 time_step
-float64[2] command
-float64[5] lambda
-float64[4] gamma
-PosePolar polar_error
-float64[2] backstep_set_point
-float64[2] backstep_set_point_dot
-float64[2] backstep_process_value
-float64[2] backstep_error
-float64[2] backstep_command
-float64[2] linear_dynamics_command
+++ /dev/null
-float64 range
-float64 angle
-float64 orientation
<build_depend>controller_interface</build_depend>
<build_depend>effort_controllers</build_depend>
<build_depend>geometry_msgs</build_depend>
- <build_depend>message_generation</build_depend>
<build_depend>nav_msgs</build_depend>
+ <build_depend>nonsmooth_backstep_controller_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>tf</build_depend>
<build_export_depend>Eigen3</build_export_depend>
<build_export_depend>effort_controllers</build_export_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<build_export_depend>nav_msgs</build_export_depend>
+ <build_export_depend>nonsmooth_backstep_controller_msgs</build_export_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>tf</build_export_depend>
<exec_depend>Eigen3</exec_depend>
<exec_depend>controller_interface</exec_depend>
<exec_depend>effort_controllers</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
- <exec_depend>message_runtime</exec_depend>
<exec_depend>nav_msgs</exec_depend>
+ <exec_depend>nonsmooth_backstep_controller_msgs</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>tf</exec_depend>
#include <nonsmooth_backstep_controller/nonsmooth_backstep_controller.h>
-#define sqr(x) (x*x)
-#define cub(x) (x*x*x)
+#define sqr(x) ((x)*(x))
+#define cub(x) ((x)*(x)*(x))
namespace effort_controllers
{
std::string base_frame_id="base_link";
node_.param("base_frame_id",base_frame_id,base_frame_id);
- status_publisher_.reset(new realtime_tools::RealtimePublisher<nonsmooth_backstep_controller::NonSmoothBackstepControllerStatus>(node_,"status",1));
+ status_publisher_.reset(new realtime_tools::RealtimePublisher<nonsmooth_backstep_controller_msgs::NonSmoothBackstepControllerStatus>(node_,"status",1));
status_publisher_->msg_.header.frame_id=odom_frame_id;
odom_publisher_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(node_,"odom",100));