git commit -m "first commit for v2"
This commit is contained in:
233
Devices/Packages/diff_wheel_plugin/CMakeLists.txt
Executable file
233
Devices/Packages/diff_wheel_plugin/CMakeLists.txt
Executable file
@@ -0,0 +1,233 @@
|
||||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(diff_wheel_plugin)
|
||||
|
||||
## Compile as C++17, supported in ROS Kinetic and newer
|
||||
add_compile_options(-std=c++17)
|
||||
|
||||
## Find catkin macros and libraries
|
||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||
## is used, also find other catkin packages
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
std_msgs
|
||||
models
|
||||
pluginlib
|
||||
realtime_tools
|
||||
geometry_msgs
|
||||
delta_modbus
|
||||
md_controller
|
||||
nav_2d_utils
|
||||
)
|
||||
|
||||
## System dependencies are found with CMake's conventions
|
||||
find_package(Boost REQUIRED COMPONENTS system)
|
||||
|
||||
|
||||
## Uncomment this if the package has a setup.py. This macro ensures
|
||||
## modules and global scripts declared therein get installed
|
||||
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
|
||||
# catkin_python_setup()
|
||||
|
||||
################################################
|
||||
## Declare ROS messages, services and actions ##
|
||||
################################################
|
||||
|
||||
## To declare and build messages, services or actions from within this
|
||||
## package, follow these steps:
|
||||
## * Let MSG_DEP_SET be the set of packages whose message types you use in
|
||||
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
|
||||
## * In the file package.xml:
|
||||
## * add a build_depend tag for "message_generation"
|
||||
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
|
||||
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
|
||||
## but can be declared for certainty nonetheless:
|
||||
## * add a exec_depend tag for "message_runtime"
|
||||
## * In this file (CMakeLists.txt):
|
||||
## * add "message_generation" and every package in MSG_DEP_SET to
|
||||
## find_package(catkin REQUIRED COMPONENTS ...)
|
||||
## * add "message_runtime" and every package in MSG_DEP_SET to
|
||||
## catkin_package(CATKIN_DEPENDS ...)
|
||||
## * uncomment the add_*_files sections below as needed
|
||||
## and list every .msg/.srv/.action file to be processed
|
||||
## * uncomment the generate_messages entry below
|
||||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
|
||||
|
||||
## Generate messages in the 'msg' folder
|
||||
# add_message_files(
|
||||
# FILES
|
||||
# Message1.msg
|
||||
# Message2.msg
|
||||
# )
|
||||
|
||||
## Generate services in the 'srv' folder
|
||||
# add_service_files(
|
||||
# FILES
|
||||
# Service1.srv
|
||||
# Service2.srv
|
||||
# )
|
||||
|
||||
## Generate actions in the 'action' folder
|
||||
# add_action_files(
|
||||
# FILES
|
||||
# Action1.action
|
||||
# Action2.action
|
||||
# )
|
||||
|
||||
## Generate added messages and services with any dependencies listed here
|
||||
# generate_messages(
|
||||
# DEPENDENCIES
|
||||
# std_msgs # Or other packages containing msgs
|
||||
# )
|
||||
|
||||
################################################
|
||||
## Declare ROS dynamic reconfigure parameters ##
|
||||
################################################
|
||||
|
||||
## To declare and build dynamic reconfigure parameters within this
|
||||
## package, follow these steps:
|
||||
## * In the file package.xml:
|
||||
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
|
||||
## * In this file (CMakeLists.txt):
|
||||
## * add "dynamic_reconfigure" to
|
||||
## find_package(catkin REQUIRED COMPONENTS ...)
|
||||
## * uncomment the "generate_dynamic_reconfigure_options" section below
|
||||
## and list every .cfg file to be processed
|
||||
|
||||
## Generate dynamic reconfigure parameters in the 'cfg' folder
|
||||
# generate_dynamic_reconfigure_options(
|
||||
# cfg/DynReconf1.cfg
|
||||
# cfg/DynReconf2.cfg
|
||||
# )
|
||||
|
||||
###################################
|
||||
## catkin specific configuration ##
|
||||
###################################
|
||||
## The catkin_package macro generates cmake config files for your package
|
||||
## Declare things to be passed to dependent projects
|
||||
## INCLUDE_DIRS: uncomment this if your package contains header files
|
||||
## LIBRARIES: libraries you create in this project that dependent projects also need
|
||||
## CATKIN_DEPENDS: catkin_packages dependent projects also need
|
||||
## DEPENDS: system dependencies of this project that dependent projects also need
|
||||
catkin_package(
|
||||
INCLUDE_DIRS include
|
||||
LIBRARIES diff_wheel_plugin
|
||||
CATKIN_DEPENDS roscpp geometry_msgs std_msgs realtime_tools
|
||||
DEPENDS Boost
|
||||
)
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
## Specify additional locations of header files
|
||||
## Your package locations should be listed before other locations
|
||||
include_directories(
|
||||
include
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${Boost_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
## Declare a C++ library
|
||||
add_library(${PROJECT_NAME}
|
||||
src/wheel_plugin.cpp
|
||||
# src/encoder_plugin.cpp
|
||||
)
|
||||
|
||||
## Add cmake target dependencies of the library
|
||||
## as an example, code may need to be generated before libraries
|
||||
## either from message generation or dynamic reconfigure
|
||||
add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
## Declare a C++ executable
|
||||
## With catkin_make all packages are built within a single CMake context
|
||||
## The recommended prefix ensures that target names across packages don't collide
|
||||
add_executable(diff_wheel_feedback src/diff_wheel_feedback.cpp)
|
||||
add_executable(diff_wheel_controller src/diff_wheel_controller.cpp)
|
||||
|
||||
## Rename C++ executable without prefix
|
||||
## The above recommended prefix causes long target names, the following renames the
|
||||
## target back to the shorter version for ease of user use
|
||||
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
|
||||
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
|
||||
|
||||
## Add cmake target dependencies of the executable
|
||||
## same as for the library above
|
||||
add_dependencies(diff_wheel_feedback ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
add_dependencies(diff_wheel_controller ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
## Specify libraries to link a library or executable target against
|
||||
target_link_libraries(${PROJECT_NAME}
|
||||
${Boost_LIBRARIES}
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
|
||||
target_link_libraries(diff_wheel_feedback
|
||||
${PROJECT_NAME}
|
||||
${Boost_LIBRARIES}
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
|
||||
target_link_libraries(diff_wheel_controller
|
||||
${PROJECT_NAME}
|
||||
${Boost_LIBRARIES}
|
||||
${catkin_LIBRARIES}
|
||||
)
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
# all install targets should use catkin DESTINATION variables
|
||||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
|
||||
|
||||
## Mark executable scripts (Python etc.) for installation
|
||||
## in contrast to setup.py, you can choose the destination
|
||||
# catkin_install_python(PROGRAMS
|
||||
# scripts/my_python_script
|
||||
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark executables for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
|
||||
install(TARGETS diff_wheel_feedback diff_wheel_controller
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
||||
|
||||
## Mark libraries for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
|
||||
install(TARGETS ${PROJECT_NAME}
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
|
||||
)
|
||||
|
||||
## Mark cpp header files for installation
|
||||
install(DIRECTORY include/${PROJECT_NAME}/
|
||||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
||||
FILES_MATCHING PATTERN "*.h"
|
||||
PATTERN ".svn" EXCLUDE
|
||||
)
|
||||
|
||||
install(DIRECTORY
|
||||
launch
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
||||
)
|
||||
|
||||
## Mark other files for installation (e.g. launch and bag files, etc.)
|
||||
# install(FILES
|
||||
# # myfile1
|
||||
# # myfile2
|
||||
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
||||
# )
|
||||
|
||||
#############
|
||||
## Testing ##
|
||||
#############
|
||||
|
||||
## Add gtest based cpp test target and link libraries
|
||||
# catkin_add_gtest(${PROJECT_NAME}-test test/test_diff_wheel_plugin.cpp)
|
||||
# if(TARGET ${PROJECT_NAME}-test)
|
||||
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
|
||||
# endif()
|
||||
|
||||
## Add folders to be run by python nosetests
|
||||
# catkin_add_nosetests(test)
|
||||
17
Devices/Packages/diff_wheel_plugin/include/diff_wheel_plugin/command.h
Executable file
17
Devices/Packages/diff_wheel_plugin/include/diff_wheel_plugin/command.h
Executable file
@@ -0,0 +1,17 @@
|
||||
#ifndef __DIFF_WHEEL_PLUGIN_COMMAND_H_INCLUDED_
|
||||
#define __DIFF_WHEEL_PLUGIN_COMMAND_H_INCLUDED_
|
||||
|
||||
#include <ros/ros.h>
|
||||
|
||||
namespace diff_wheel_plugin
|
||||
{
|
||||
class WheelCommand
|
||||
{
|
||||
public:
|
||||
double vel_wheel;
|
||||
ros::Time stamp;
|
||||
|
||||
WheelCommand() : vel_wheel(0.0), stamp(0.0) {}
|
||||
};
|
||||
} // namespace diff_wheel_plugin
|
||||
#endif
|
||||
159
Devices/Packages/diff_wheel_plugin/include/diff_wheel_plugin/wheel_plugin.h
Executable file
159
Devices/Packages/diff_wheel_plugin/include/diff_wheel_plugin/wheel_plugin.h
Executable file
@@ -0,0 +1,159 @@
|
||||
#ifndef __ROS_DIFF_WHEEL_PLUGIN_H_INCLUDED_
|
||||
#define __ROS_DIFF_WHEEL_PLUGIN_H_INCLUDED_
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <std_msgs/Float32.h>
|
||||
#include "diff_wheel_plugin/command.h"
|
||||
#include <realtime_tools/realtime_buffer.h>
|
||||
#include <realtime_tools/realtime_publisher.h>
|
||||
// Boost
|
||||
#include <boost/thread.hpp>
|
||||
#include <boost/make_shared.hpp>
|
||||
//plugin
|
||||
#include <models/BaseSteerDrive.h>
|
||||
|
||||
|
||||
namespace diff_wheel_plugin
|
||||
{
|
||||
/**
|
||||
* @class WheelPlugin
|
||||
*/
|
||||
class WheelPlugin : public models::BaseSteerDrive
|
||||
{
|
||||
public:
|
||||
|
||||
/**
|
||||
* @brief Contructor
|
||||
*/
|
||||
WheelPlugin();
|
||||
|
||||
/**
|
||||
* @brief Contructor
|
||||
* @param[in] nh NodeHandle
|
||||
* @param[in] name The name to give this instance of the model base
|
||||
*/
|
||||
WheelPlugin(ros::NodeHandle & nh, const std::string &name);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Decontructor
|
||||
*/
|
||||
virtual ~WheelPlugin();
|
||||
|
||||
/**
|
||||
* @brief Init
|
||||
* @param[in] nh NodeHandle
|
||||
* @param name The name to give this instance of the model base
|
||||
*/
|
||||
virtual void initialize(ros::NodeHandle & nh, const std::string &name) override;
|
||||
|
||||
/**
|
||||
* @brief Constructs
|
||||
* @param name Check model is deady
|
||||
* @return true, if model is ready, false otherwise
|
||||
*/
|
||||
virtual bool Ready() override;
|
||||
|
||||
/**
|
||||
* @brief Get the velocity limit on axis(index).
|
||||
* @return Velocity limit specified in SDF
|
||||
*/
|
||||
virtual double GetVelocityLimit(unsigned int _index) override;
|
||||
|
||||
/**
|
||||
* @brief Set the velocity limit on a joint axis.
|
||||
* @param[in] _velocity Velocity limit for the axis.
|
||||
*/
|
||||
virtual void SetVelocityLimit(double _velocity) override;
|
||||
|
||||
/**
|
||||
* @brief Get the rotation rate of an axis(index)
|
||||
* @return The rotaional velocity of the joint axis. (rad/s)
|
||||
*/
|
||||
virtual double GetVelocity() override;
|
||||
|
||||
/**
|
||||
* @brief Set the velocity of an axis(index).
|
||||
* In ODE and Bullet, the SetVelocityMaximal function is used to
|
||||
* set the velocity of the child link relative to the parent.
|
||||
* In Simbody and DART, this function updates the velocity state,
|
||||
* which has a recursive effect on the rest of the chain.
|
||||
* @param[in] _vel Velocity.
|
||||
*/
|
||||
virtual void SetVelocity(double _vel) override;
|
||||
|
||||
/**
|
||||
* @brief Get the position of an axis according to its index.
|
||||
*
|
||||
* For rotational axes, the value is in radians. For prismatic axes,
|
||||
* it is in meters.
|
||||
*
|
||||
* For static models, it returns the static joint position.
|
||||
*
|
||||
* It returns ignition::math::NAN_D in case the position can't be
|
||||
* obtained. For instance, if the index is invalid, if the joint is
|
||||
* fixed, etc.
|
||||
*
|
||||
* Subclasses can't override this method. See PositionImpl instead.
|
||||
*
|
||||
* @return Current position of the axis.
|
||||
* @sa PositionImpl
|
||||
*/
|
||||
virtual double Position() override;
|
||||
|
||||
/**
|
||||
* @brief The child links of this joint are updated based on desired
|
||||
* position. And all the links connected to the child link of this joint
|
||||
* except through the parent link of this joint moves with the child
|
||||
* link.
|
||||
* @param[in] _position Position to set the joint to.
|
||||
* unspecified, pure kinematic teleportation.
|
||||
* link with respect to the world frame will remain the same after
|
||||
* setting the position. By default this is false, which means there are
|
||||
* no guarantees about what the child link's world velocity will be after
|
||||
* the position is changed (the behavior is determined by the underlying
|
||||
* physics engine).
|
||||
*
|
||||
* @note{Only ODE and Bullet support _preserveWorldVelocity being true.}
|
||||
*/
|
||||
virtual void SetPosition(const double _position) override;
|
||||
|
||||
private:
|
||||
|
||||
/**
|
||||
* @brief Brake by away SetVelocity(0.0)
|
||||
*/
|
||||
void brake() { this->SetVelocity(0.0); }
|
||||
|
||||
/**
|
||||
* @brief call back from a subscriber
|
||||
*/
|
||||
void DLS_Callback(const std_msgs::Float32::ConstPtr & msg);
|
||||
|
||||
/**
|
||||
* @brief Do stuff when create boost::Thread
|
||||
*/
|
||||
void DoStuff(void);
|
||||
|
||||
ros::NodeHandle nh_;
|
||||
ros::NodeHandle nh_priv_;
|
||||
std::string name_;
|
||||
bool initialized_;
|
||||
bool is_ready_;
|
||||
int m_subscribe_queue_size_;
|
||||
double update_rate_;
|
||||
boost::thread * m_publish_thread_;
|
||||
boost::mutex callback_mutex_;
|
||||
std_msgs::Float32::ConstPtr m_measurement_;
|
||||
|
||||
bool allow_multiple_command_publishers_;
|
||||
realtime_tools::RealtimeBuffer<diff_wheel_plugin::WheelCommand> command_;
|
||||
diff_wheel_plugin::WheelCommand command_struct_;
|
||||
double command_timeout_;
|
||||
ros::Subscriber mesurement_sub_;
|
||||
boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Float32>> wheel_pub_;
|
||||
};
|
||||
|
||||
} // namespace diff_wheel_plugin
|
||||
|
||||
#endif // __ROS_DIFF_WHEEL_PLUGIN_H_INCLUDED_
|
||||
16
Devices/Packages/diff_wheel_plugin/launch/run.launch
Executable file
16
Devices/Packages/diff_wheel_plugin/launch/run.launch
Executable file
@@ -0,0 +1,16 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<arg name="output_screen" default="screen"/>
|
||||
<node pkg="diff_wheel_plugin" type="diff_wheel_feedback" name="diff_wheel_feedback" output="$(arg output_screen)">
|
||||
<param name="ip_address" value="192.168.1.5"/>
|
||||
<param name="port" value="502"/>
|
||||
<param name="publish_rate" value="50"/>
|
||||
<param name="start_bit" value="111"/>
|
||||
<param name="end_bit" value="114"/>
|
||||
</node>
|
||||
|
||||
<node pkg="diff_wheel_plugin" type="diff_wheel_controller" name="diff_wheel_controller" output="screen">
|
||||
<rosparam command="load" file="$(find md_controller)/motorInfomation.yaml"/>
|
||||
<param name="port_name" type="str" value="/dev/USB_MD200"/>
|
||||
</node>
|
||||
</launch>
|
||||
89
Devices/Packages/diff_wheel_plugin/package.xml
Executable file
89
Devices/Packages/diff_wheel_plugin/package.xml
Executable file
@@ -0,0 +1,89 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>diff_wheel_plugin</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The diff_wheel_plugin package</description>
|
||||
|
||||
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||
<!-- Example: -->
|
||||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
||||
<maintainer email="robotics@todo.todo">robotics</maintainer>
|
||||
|
||||
|
||||
<!-- One license tag required, multiple allowed, one license per tag -->
|
||||
<!-- Commonly used license strings: -->
|
||||
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
|
||||
<license>TODO</license>
|
||||
|
||||
|
||||
<!-- Url tags are optional, but multiple are allowed, one per tag -->
|
||||
<!-- Optional attribute type can be: website, bugtracker, or repository -->
|
||||
<!-- Example: -->
|
||||
<!-- <url type="website">http://wiki.ros.org/diff_wheel_plugin</url> -->
|
||||
|
||||
|
||||
<!-- Author tags are optional, multiple are allowed, one per tag -->
|
||||
<!-- Authors do not have to be maintainers, but could be -->
|
||||
<!-- Example: -->
|
||||
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
|
||||
|
||||
|
||||
<!-- The *depend tags are used to specify dependencies -->
|
||||
<!-- Dependencies can be catkin packages or system dependencies -->
|
||||
<!-- Examples: -->
|
||||
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
|
||||
<!-- <depend>roscpp</depend> -->
|
||||
<!-- Note that this is equivalent to the following: -->
|
||||
<!-- <build_depend>roscpp</build_depend> -->
|
||||
<!-- <exec_depend>roscpp</exec_depend> -->
|
||||
<!-- Use build_depend for packages you need at compile time: -->
|
||||
<!-- <build_depend>message_generation</build_depend> -->
|
||||
<!-- Use build_export_depend for packages you need in order to build against this package: -->
|
||||
<!-- <build_export_depend>message_generation</build_export_depend> -->
|
||||
<!-- Use buildtool_depend for build tool packages: -->
|
||||
<!-- <buildtool_depend>catkin</buildtool_depend> -->
|
||||
<!-- Use exec_depend for packages you need at runtime: -->
|
||||
<!-- <exec_depend>message_runtime</exec_depend> -->
|
||||
<!-- Use test_depend for packages you need only for testing: -->
|
||||
<!-- <test_depend>gtest</test_depend> -->
|
||||
<!-- Use doc_depend for packages you need only for building documentation: -->
|
||||
<!-- <doc_depend>doxygen</doc_depend> -->
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_depend>geometry_msgs</build_depend>
|
||||
<build_depend>delta_modbus_tcp</build_depend>
|
||||
<build_depend>md_controller</build_depend>
|
||||
<build_depend>models</build_depend>
|
||||
<build_depend>pluginlib</build_depend>
|
||||
<build_depend>realtime_tools</build_depend>
|
||||
<build_depend>nav_2d_utils</build_depend>
|
||||
|
||||
<build_export_depend>std_msgs</build_export_depend>
|
||||
<build_export_depend>geometry_msgs</build_export_depend>
|
||||
<build_export_depend>delta_modbus_tcp</build_export_depend>
|
||||
<build_export_depend>md_controller</build_export_depend>
|
||||
<build_export_depend>models</build_export_depend>
|
||||
<build_export_depend>pluginlib</build_export_depend>
|
||||
<build_export_depend>realtime_tools</build_export_depend>
|
||||
<build_export_depend>nav_2d_utils</build_export_depend>
|
||||
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
<exec_depend>geometry_msgs</exec_depend>
|
||||
<exec_depend>delta_modbus_tcp</exec_depend>
|
||||
<exec_depend>md_controller</exec_depend>
|
||||
<exec_depend>models</exec_depend>
|
||||
<exec_depend>pluginlib</exec_depend>
|
||||
<exec_depend>realtime_tools</exec_depend>
|
||||
<exec_depend>nav_2d_utils</exec_depend>
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
<!-- Other tools can request additional information be placed here -->
|
||||
<models plugin="${prefix}/plugins.xml" />
|
||||
</export>
|
||||
</package>
|
||||
9
Devices/Packages/diff_wheel_plugin/plugins.xml
Executable file
9
Devices/Packages/diff_wheel_plugin/plugins.xml
Executable file
@@ -0,0 +1,9 @@
|
||||
<library path="lib/libdiff_wheel_plugin">
|
||||
<class name="WheelPlugin" type="diff_wheel_plugin::WheelPlugin" base_class_type="models::BaseSteerDrive">
|
||||
<description></description>
|
||||
</class>
|
||||
|
||||
<class name="EncoderPlugin" type="diff_wheel_plugin::EncoderPlugin" base_class_type="models::BaseAbsoluteEncoder">
|
||||
<description></description>
|
||||
</class>
|
||||
</library>
|
||||
201
Devices/Packages/diff_wheel_plugin/src/diff_wheel_controller.cpp
Executable file
201
Devices/Packages/diff_wheel_plugin/src/diff_wheel_controller.cpp
Executable file
@@ -0,0 +1,201 @@
|
||||
#include <ros/ros.h>
|
||||
#include <XmlRpcValue.h>
|
||||
#include <boost/thread/thread.hpp>
|
||||
#include "md_controller/md_controller.h"
|
||||
#include "md_controller/diagnostic.h"
|
||||
#include "md_controller/md_controller_subscriber.h"
|
||||
#include "libserial/udevadm_info.h"
|
||||
#include <cstdlib>
|
||||
#include <XmlRpcException.h>
|
||||
|
||||
/* define struct */
|
||||
typedef struct device{
|
||||
std::string _port;
|
||||
int _baud;
|
||||
}device_t;
|
||||
|
||||
|
||||
bool findDevice(ros::NodeHandlePtr nh, std::string node_name, device_t *dv) {
|
||||
ROS_INFO("loadParam() - node_name: %s", node_name.c_str());
|
||||
if(!nh->param(node_name + "/baudrate", dv->_baud, dv->_baud))
|
||||
{
|
||||
if(!nh->getParam("baudrate", dv->_baud))
|
||||
return false;
|
||||
}
|
||||
|
||||
ROS_INFO("product");
|
||||
std::string product; //port name
|
||||
if(!nh->param(node_name + "/product", product, product)) {}
|
||||
else if(!nh->getParam("product", product)) {}
|
||||
else
|
||||
{
|
||||
udevadmInfo *ludev = new udevadmInfo(product.c_str());
|
||||
if(ludev->init() == EXIT_FAILURE) {}
|
||||
if(ludev->scanDevices())
|
||||
{
|
||||
strcpy(dv->_port.data(), ludev->port);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
ROS_INFO("port_name");
|
||||
if(!nh->param(node_name + "/port_name", dv->_port, dv->_port))
|
||||
{
|
||||
if(!nh->getParam("port_name", dv->_port))
|
||||
return false;
|
||||
}
|
||||
|
||||
ROS_WARN("Can not scan device from /product. So try to use /port_name is %s", dv->_port.c_str());
|
||||
return true;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief shortcut to read a member from a XmlRpcValue, or to return a defaultvalue, it the member does not exist
|
||||
*/
|
||||
template<class T> static T readMember(XmlRpc::XmlRpcValue & value, const std::string & member, const T & defaultvalue)
|
||||
{
|
||||
try
|
||||
{
|
||||
if(value.hasMember(member))
|
||||
return value[member];
|
||||
return defaultvalue;
|
||||
}
|
||||
catch(const XmlRpc::XmlRpcException& e)
|
||||
{
|
||||
ROS_WARN_STREAM( "'"<<member << "' "<< e.getMessage() << '\n');
|
||||
return defaultvalue;
|
||||
}
|
||||
}
|
||||
/**********************************************************************
|
||||
* MAIN
|
||||
***********************************************************************/
|
||||
int main(int argc,char **argv)
|
||||
{
|
||||
/* create ros ndoe */
|
||||
ros::init(argc, argv, "MD");
|
||||
ros::NodeHandlePtr nh = boost::make_shared<ros::NodeHandle>();
|
||||
std::string node_name = ros::this_node::getName();
|
||||
ROS_INFO("%s.cpp-node_name: %s", node_name.c_str(), node_name.c_str());
|
||||
|
||||
/* connect with the server */
|
||||
std::string diagnostic_topic = "MD_diagnostic";
|
||||
MD::Diagnostic::init(*nh, diagnostic_topic, "MD md_controller");
|
||||
|
||||
|
||||
XmlRpc::XmlRpcValue drivers;
|
||||
if(!nh->getParam(node_name + "/drivers", drivers) || drivers.size() < 1)
|
||||
{
|
||||
ROS_ERROR("%s: no driver found in yaml-file, please check configuration. Aborting...", node_name.c_str());
|
||||
MD::Diagnostic::update(MD::DIAGNOSTIC_STATUS::CONFIGURATION_ERROR, " No driver found in yaml-file");
|
||||
return 2;
|
||||
}
|
||||
|
||||
std::vector<boost::shared_ptr<MD::Subscriber>> p_md_controller_subscriber;
|
||||
for(XmlRpc::XmlRpcValue::iterator object_iter = drivers.begin(); object_iter != drivers.end(); ++object_iter)
|
||||
{
|
||||
std::string topic_name = readMember<std::string>(object_iter->second, "toppic", "");
|
||||
int subscribe_queue_size = readMember<int>(object_iter->second, "subscribe_queue_size", 1);
|
||||
ROS_INFO("%s: initializing toppic \"%s\" queue_size \"%d\"...", node_name.c_str(), topic_name.c_str(), subscribe_queue_size);
|
||||
p_md_controller_subscriber.push_back(boost::make_shared<MD::Subscriber>(*nh, object_iter));
|
||||
}
|
||||
|
||||
device_t dv;
|
||||
if(findDevice(nh, node_name, &dv))
|
||||
{
|
||||
ROS_INFO("%s: found device successfull", node_name.c_str());
|
||||
}
|
||||
else
|
||||
{
|
||||
ROS_ERROR("%s: Error when find device", node_name.c_str());
|
||||
return 2;
|
||||
}
|
||||
|
||||
uint8_t rate = 50; // Hz
|
||||
ros::Rate loop_rate(rate);
|
||||
|
||||
if (p_md_controller_subscriber.empty()) {
|
||||
ROS_WARN("No subscribers available!");
|
||||
return 1;
|
||||
}
|
||||
|
||||
while (ros::ok())
|
||||
{
|
||||
ROS_INFO("%s: Conecting port name %s with baudrate %d ...", node_name.c_str(), dv._port.c_str(), dv._baud);
|
||||
boost::shared_ptr<MD::MdController> md_controller = boost::make_shared<MD::MdController>(nh, dv._port.c_str(), dv._baud, PARITY_NONE, DATABIT_8, STOPBIT_1);
|
||||
ros::Duration(1.0).sleep();
|
||||
const std::string password = "robotics"; // Replace with the correct password
|
||||
// First, set to RS232
|
||||
std::string command = "sudo -S -k echo rs232 > /sys/class/sp339_mode_ctl/uartMode";
|
||||
std::string full_command = "echo '" +password + "' | " + command;
|
||||
system(full_command.c_str());
|
||||
|
||||
// Sleep for 0.5 seconds
|
||||
ros::Duration(1.0).sleep();
|
||||
|
||||
// Now, set to RS485
|
||||
command = "sudo -S -k echo rs485 > /sys/class/sp339_mode_ctl/uartMode";
|
||||
full_command = "echo '" + password + "' | " + command;
|
||||
system(full_command.c_str());
|
||||
|
||||
for(auto &p_sub : p_md_controller_subscriber)
|
||||
{
|
||||
md_controller->pid_break(p_sub->slave_id);
|
||||
md_controller->pid_break(p_sub->slave_id);
|
||||
}
|
||||
int v_min = 60;
|
||||
while(ros::ok() && md_controller->_connected)
|
||||
{
|
||||
for(auto it = p_md_controller_subscriber.begin(); it != p_md_controller_subscriber.end(); ++it)
|
||||
{
|
||||
auto &p_sub = *it;
|
||||
if(p_sub->isWheelTriggered())
|
||||
{
|
||||
int16_t rotate_speed_wheel;
|
||||
{
|
||||
boost::lock_guard<boost::mutex> publish_lockguard(p_sub->m_measurement_mutex);
|
||||
rotate_speed_wheel = p_sub->speed;
|
||||
}
|
||||
|
||||
if(std::abs(rotate_speed_wheel) > 0)
|
||||
{
|
||||
int sign = (rotate_speed_wheel / abs(rotate_speed_wheel)) > 0 ? 1 : -1;
|
||||
int16_t speed = abs(rotate_speed_wheel) < v_min? (int)(sign * v_min) : rotate_speed_wheel;
|
||||
md_controller->pid_vel_cmd(p_sub->slave_id, speed);
|
||||
// ROS_INFO("%x %d", p_sub->slave_id, speed);
|
||||
}
|
||||
else
|
||||
{
|
||||
md_controller->pid_break(p_sub->slave_id);
|
||||
if(abs(rotate_speed_wheel) > 0) ROS_INFO("%x Brake %d", p_sub->slave_id, rotate_speed_wheel);
|
||||
}
|
||||
p_sub->scheduleWheelController(false);
|
||||
}
|
||||
|
||||
if(p_sub->isWheelLastestTriggered())
|
||||
{
|
||||
int16_t rotate_speed_wheel;
|
||||
{
|
||||
boost::lock_guard<boost::mutex> publish_lockguard(p_sub->m_measurement_mutex);
|
||||
rotate_speed_wheel = p_sub->speed;
|
||||
}
|
||||
md_controller->pid_stop(p_sub->slave_id);
|
||||
if(std::abs(rotate_speed_wheel) > 0) ROS_WARN("%x stop %d", p_sub->slave_id, rotate_speed_wheel);
|
||||
p_sub->scheduleWheelController(false);
|
||||
}
|
||||
}
|
||||
loop_rate.sleep();
|
||||
ros::spinOnce();
|
||||
}
|
||||
ros::spinOnce();
|
||||
for(auto &p_sub : p_md_controller_subscriber)
|
||||
{
|
||||
md_controller->pid_break(p_sub->slave_id);
|
||||
md_controller->pid_break(p_sub->slave_id);
|
||||
}
|
||||
md_controller->close_port();
|
||||
}
|
||||
ros::spin();
|
||||
return 0;
|
||||
}
|
||||
|
||||
81
Devices/Packages/diff_wheel_plugin/src/diff_wheel_feedback.cpp
Executable file
81
Devices/Packages/diff_wheel_plugin/src/diff_wheel_feedback.cpp
Executable file
@@ -0,0 +1,81 @@
|
||||
#include <ros/ros.h>
|
||||
#include <boost/thread.hpp>
|
||||
#include "delta_modbus/delta_modbus_tcp.h"
|
||||
#include <std_msgs/Float32.h>
|
||||
|
||||
double combine_uint16_to_double(uint16_t high, uint16_t low) {
|
||||
// Chuyển đổi high thành double và dịch nó sang trái 16 bit
|
||||
double result = (double)high * 65536.0; // 65536 = 2^16
|
||||
|
||||
// Thêm low vào kết quả
|
||||
result += (double)low;
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/**********************************************************************
|
||||
* MAIN
|
||||
***********************************************************************/
|
||||
int main(int argc, char** argv) {
|
||||
ros::init(argc, argv, "diff_encoder_node");
|
||||
ros::NodeHandle nh;
|
||||
ros::NodeHandle nh_node("~");
|
||||
std::string node_name = ros::this_node::getName();
|
||||
ROS_INFO("node_name: %s", node_name.c_str());
|
||||
|
||||
std::string ip_address;
|
||||
int port;
|
||||
|
||||
if(!nh_node.getParam("ip_address", ip_address))
|
||||
{
|
||||
ROS_ERROR("Could not find 'ip_address' in node handle");
|
||||
return 1;
|
||||
}
|
||||
if(!nh_node.getParam("port", port))
|
||||
{
|
||||
ROS_ERROR("Could not find 'port' in node handle");
|
||||
return 1;
|
||||
}
|
||||
|
||||
int id;
|
||||
nh_node.param("id", id, 1);
|
||||
double rate;
|
||||
nh_node.param("publish_rate", rate, 20.0);
|
||||
|
||||
int start, end;
|
||||
nh_node.param("start_bit", start, 101);
|
||||
nh_node.param("end_bit", end, 103);
|
||||
|
||||
ROS_INFO("%s: start_bit: %d end_bit: %d ", node_name.c_str(), start, end);
|
||||
|
||||
ros::Publisher left_encoder_pub = nh.advertise<std_msgs::Float32>("left_encoder", 1);
|
||||
ros::Publisher right_encoder_pub = nh.advertise<std_msgs::Float32>("right_encoder", 1);
|
||||
DELTA_NAMESPACE::PLC *plc = NULL;
|
||||
plc = new DELTA_NAMESPACE::PLC(ip_address, port, id);
|
||||
ros::Rate r(rate);
|
||||
uint16_t dataD[4];
|
||||
float left_encoder, righ_encoder;
|
||||
while (ros::ok())
|
||||
{
|
||||
plc->connect();
|
||||
while (ros::ok() && plc->checkConnected())
|
||||
{
|
||||
plc->mulGetD(start, end, dataD);
|
||||
std::memcpy(reinterpret_cast<void*>(&righ_encoder), reinterpret_cast<void const*>(&dataD[0]), sizeof left_encoder);
|
||||
std::memcpy(reinterpret_cast<void*>(&left_encoder), reinterpret_cast<void const*>(&dataD[2]), sizeof righ_encoder);
|
||||
std_msgs::Float32 left_encoder_msg, righ_encoder_msg;
|
||||
left_encoder_msg.data = left_encoder * 2 * M_PI;
|
||||
righ_encoder_msg.data = righ_encoder * 2 * M_PI;
|
||||
left_encoder_pub.publish(left_encoder_msg);
|
||||
right_encoder_pub.publish(righ_encoder_msg);
|
||||
r.sleep();
|
||||
ros::spinOnce();
|
||||
}
|
||||
ros::spinOnce();
|
||||
}
|
||||
|
||||
ros::spin();
|
||||
plc = NULL;
|
||||
delete(plc);
|
||||
return 0;
|
||||
}
|
||||
192
Devices/Packages/diff_wheel_plugin/src/wheel_plugin.cpp
Executable file
192
Devices/Packages/diff_wheel_plugin/src/wheel_plugin.cpp
Executable file
@@ -0,0 +1,192 @@
|
||||
#include "diff_wheel_plugin/wheel_plugin.h"
|
||||
#include <pluginlib/class_list_macros.hpp>
|
||||
#include <nav_2d_utils/parameters.h>
|
||||
#include <nav_2d_utils/conversions.h>
|
||||
#include <nav_2d_utils/tf_help.h>
|
||||
#include <nav_2d_utils/path_ops.h>
|
||||
|
||||
|
||||
namespace diff_wheel_plugin
|
||||
{
|
||||
|
||||
WheelPlugin::WheelPlugin()
|
||||
: command_timeout_(0.5)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
WheelPlugin::WheelPlugin(ros::NodeHandle & nh, const std::string &name)
|
||||
: command_timeout_(0.5)
|
||||
{
|
||||
initialize(nh, name);
|
||||
}
|
||||
|
||||
|
||||
WheelPlugin::~WheelPlugin()
|
||||
{
|
||||
if (m_publish_thread_)
|
||||
{
|
||||
m_publish_thread_->join();
|
||||
delete (m_publish_thread_);
|
||||
m_publish_thread_ = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void WheelPlugin::initialize(ros::NodeHandle & nh, const std::string &name)
|
||||
{
|
||||
if(!initialized_)
|
||||
{
|
||||
nh_ = nh;
|
||||
name_ = name;
|
||||
nh_priv_ = ros::NodeHandle(nh, name);
|
||||
nh_priv_.param("command_timeout", command_timeout_, 0.5);
|
||||
nh_priv_.param("subscribe_queue_size", m_subscribe_queue_size_, 1);
|
||||
nh_priv_.param("max_publish_rate", update_rate_, 100.0);
|
||||
|
||||
ROS_INFO_NAMED("WheelPlugin","Initializing on %s with command_timeout %f subscribe_queue_size %d max_publish_rate %f",
|
||||
name_.c_str(),
|
||||
command_timeout_,
|
||||
m_subscribe_queue_size_,
|
||||
update_rate_
|
||||
);
|
||||
std::string mesurement_topic;
|
||||
nh_priv_.param("mesurement_topic", mesurement_topic, std::string(""));
|
||||
std::string wheel_topic;
|
||||
nh_priv_.param("wheel_topic", wheel_topic, name_);
|
||||
|
||||
mesurement_sub_ = nh_.subscribe(mesurement_topic, m_subscribe_queue_size_, &diff_wheel_plugin::WheelPlugin::DLS_Callback, this);
|
||||
|
||||
wheel_pub_.reset(new realtime_tools::RealtimePublisher<std_msgs::Float32>(nh_, wheel_topic , 100));
|
||||
|
||||
m_publish_thread_ = new boost::thread(&diff_wheel_plugin::WheelPlugin::DoStuff,this);
|
||||
command_struct_.stamp = ros::Time::now();
|
||||
ROS_INFO_NAMED("WheelPlugin","Initializing on %s is successed", name_.c_str());
|
||||
|
||||
initialized_ = true;
|
||||
}
|
||||
}
|
||||
|
||||
bool WheelPlugin::Ready()
|
||||
{
|
||||
return is_ready_;
|
||||
}
|
||||
|
||||
double WheelPlugin::GetVelocityLimit(unsigned int _index)
|
||||
{
|
||||
throw std::bad_function_call();
|
||||
}
|
||||
|
||||
void WheelPlugin::SetVelocityLimit(double _velocity)
|
||||
{
|
||||
throw std::bad_function_call();
|
||||
}
|
||||
|
||||
double WheelPlugin::GetVelocity()
|
||||
{
|
||||
boost::lock_guard<boost::mutex> publish_lockguard(callback_mutex_);
|
||||
double result = 0.0;
|
||||
if(m_measurement_)
|
||||
{
|
||||
result = m_measurement_->data;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
void WheelPlugin::SetVelocity(double _vel)
|
||||
{
|
||||
if (!std::isfinite(_vel))
|
||||
{
|
||||
ROS_WARN_THROTTLE(1.0, "Received NaN in velocity %s command. Ignoring.", name_.c_str());
|
||||
return;
|
||||
}
|
||||
command_struct_.vel_wheel = _vel;
|
||||
command_struct_.stamp = ros::Time::now();
|
||||
command_.writeFromNonRT(command_struct_);
|
||||
ROS_DEBUG_STREAM_NAMED(name_,
|
||||
"Added values to command."
|
||||
<< "vel_wheel: " << command_struct_.vel_wheel << ", "
|
||||
<< "Stamp: " << command_struct_.stamp);
|
||||
|
||||
// ROS_INFO_STREAM_NAMED(name_,
|
||||
// "Added values to command."
|
||||
// << "vel_wheel: " << command_struct_.vel_wheel << ", "
|
||||
// << "Stamp: " << command_struct_.stamp);
|
||||
}
|
||||
|
||||
double WheelPlugin::Position()
|
||||
{
|
||||
throw std::bad_function_call();
|
||||
}
|
||||
|
||||
void WheelPlugin::SetPosition(const double _position)
|
||||
{
|
||||
throw std::bad_function_call();
|
||||
}
|
||||
|
||||
void WheelPlugin::DLS_Callback(const std_msgs::Float32::ConstPtr & msg)
|
||||
{
|
||||
boost::lock_guard<boost::mutex> publish_lockguard(callback_mutex_);
|
||||
// check that we don't have multiple publishers on the command topic
|
||||
if (!allow_multiple_command_publishers_ && mesurement_sub_.getNumPublishers() > 1)
|
||||
{
|
||||
ROS_ERROR_STREAM_THROTTLE_NAMED(1.0, name_, "Detected " << mesurement_sub_.getNumPublishers()
|
||||
<< " publishers. Only 1 publisher is allowed. Going to brake.");
|
||||
this->brake();
|
||||
return;
|
||||
}
|
||||
|
||||
if (!std::isfinite(msg->data))
|
||||
{
|
||||
ROS_WARN_THROTTLE(1.0, "Received NaN in velocity %s encoder. Ignoring.", name_.c_str());
|
||||
return;
|
||||
}
|
||||
|
||||
m_measurement_ = msg;
|
||||
}
|
||||
|
||||
void WheelPlugin::DoStuff()
|
||||
{
|
||||
ros::Rate rate(update_rate_);
|
||||
is_ready_ = true;
|
||||
ROS_INFO_NAMED("WheelPlugin","...Threading on %s is ready", name_.c_str());
|
||||
bool stoped;
|
||||
while (ros::ok())
|
||||
{
|
||||
WheelCommand curr_cmd = *(command_.readFromRT());
|
||||
ros::Time current_time = ros::Time::now();
|
||||
double dt = ros::Duration(current_time - command_struct_.stamp).toSec();
|
||||
|
||||
if(dt <= command_timeout_ && fabs(curr_cmd.vel_wheel) > 0.001)
|
||||
{
|
||||
if (wheel_pub_ && wheel_pub_->trylock())
|
||||
{
|
||||
wheel_pub_->msg_.data = curr_cmd.vel_wheel;
|
||||
wheel_pub_->unlockAndPublish();
|
||||
}
|
||||
stoped = false;
|
||||
}
|
||||
else
|
||||
{
|
||||
if(!stoped)
|
||||
{
|
||||
for(int i = 0; i < 3; i++)
|
||||
{
|
||||
if (wheel_pub_ && wheel_pub_->trylock())
|
||||
{
|
||||
wheel_pub_->msg_.data = 0;
|
||||
wheel_pub_->unlockAndPublish();
|
||||
}
|
||||
ros::Duration(0.1).sleep();
|
||||
}
|
||||
stoped = true;
|
||||
}
|
||||
}
|
||||
|
||||
rate.sleep();
|
||||
ros::spinOnce();
|
||||
}
|
||||
}
|
||||
|
||||
}; //namespace diff_wheel_plugin
|
||||
|
||||
PLUGINLIB_EXPORT_CLASS(diff_wheel_plugin::WheelPlugin, models::BaseSteerDrive)
|
||||
Reference in New Issue
Block a user