I2c behavior #17
@ -37,6 +37,7 @@ set(SOURCES
|
|||||||
|
|
||||||
|
|
||||||
add_executable(mg_bt_executor ${SOURCES})
|
add_executable(mg_bt_executor ${SOURCES})
|
||||||
|
add_executable(mg_i2cnode i2cmodule/i2cnode.cpp)
|
||||||
|
|
||||||
target_include_directories(
|
target_include_directories(
|
||||||
mg_bt_executor
|
mg_bt_executor
|
||||||
@ -45,10 +46,14 @@ target_include_directories(
|
|||||||
include
|
include
|
||||||
)
|
)
|
||||||
|
|
||||||
|
target_link_libraries(mg_i2cnode i2c)
|
||||||
|
|
||||||
ament_target_dependencies(mg_bt_executor ${PACKAGE_DEPS})
|
ament_target_dependencies(mg_bt_executor ${PACKAGE_DEPS})
|
||||||
|
ament_target_dependencies(mg_i2cnode rclcpp mg_msgs)
|
||||||
|
|
||||||
install( TARGETS
|
install( TARGETS
|
||||||
mg_bt_executor
|
mg_bt_executor
|
||||||
|
mg_i2cnode
|
||||||
DESTINATION lib/${PROJECT_NAME}
|
DESTINATION lib/${PROJECT_NAME}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|||||||
47
mg_bt/i2cmodule/i2cnode.cpp
Normal file
47
mg_bt/i2cmodule/i2cnode.cpp
Normal file
@ -0,0 +1,47 @@
|
|||||||
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
#include "mg_msgs/srv/i2c.hpp"
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <linux/i2c-dev.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
#include <i2c/smbus.h>
|
||||||
|
}
|
||||||
|
class MgI2c : public rclcpp::Node {
|
||||||
|
using I2cSrv = mg_msgs::srv::I2c;
|
||||||
|
|
||||||
|
public:
|
||||||
|
MgI2c(const std::string& name) : rclcpp::Node(name), i2c_fd_(open("/dev/i2c-1", O_RDWR)) { // NOLINT
|
||||||
|
auto cb
|
||||||
|
= [this](I2cSrv::Request::ConstSharedPtr req, I2cSrv::Response::SharedPtr resp) { send_req(req, resp); };
|
||||||
|
i2c_srv_ = create_service<I2cSrv>("/i2c", cb);
|
||||||
|
}
|
||||||
|
|
||||||
|
void send_req(I2cSrv::Request::ConstSharedPtr req, I2cSrv::Response::SharedPtr resp) const {
|
||||||
|
ioctl(i2c_fd_, I2C_SLAVE, req->addr); // NOLINT
|
||||||
|
i2c_smbus_write_byte(i2c_fd_, req->data);
|
||||||
|
int ch = 0;
|
||||||
|
|
||||||
|
rclcpp::Rate rate(100);
|
||||||
|
|
||||||
|
while (ch == 0 || (ch < 256 && ch > 0)) {
|
||||||
|
ch = i2c_smbus_read_byte(i2c_fd_);
|
||||||
|
rate.sleep();
|
||||||
|
}
|
||||||
|
resp->resp.push_back(ch);
|
||||||
|
RCLCPP_INFO(get_logger(), "Recieved %d", resp->resp.front());
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
rclcpp::Service<mg_msgs::srv::I2c>::SharedPtr i2c_srv_;
|
||||||
|
int i2c_fd_;
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, const char* const* argv) {
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
rclcpp::spin(std::make_shared<MgI2c>("i2cu"));
|
||||||
|
rclcpp::shutdown();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
@ -14,6 +14,7 @@
|
|||||||
<depend>behaviortree_ros2</depend>
|
<depend>behaviortree_ros2</depend>
|
||||||
<depend>btcpp_ros2_interfaces</depend>
|
<depend>btcpp_ros2_interfaces</depend>
|
||||||
<depend>mg_msgs</depend>
|
<depend>mg_msgs</depend>
|
||||||
|
<depend>libi2c-dev</depend>
|
||||||
|
|
||||||
<test_depend>ament_lint_auto</test_depend>
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
<test_depend>ament_lint_common</test_depend>
|
<test_depend>ament_lint_common</test_depend>
|
||||||
|
|||||||
@ -2,6 +2,7 @@
|
|||||||
|
|
||||||
#include "behaviortree_cpp/xml_parsing.h"
|
#include "behaviortree_cpp/xml_parsing.h"
|
||||||
#include "tree_nodes/calib.hpp"
|
#include "tree_nodes/calib.hpp"
|
||||||
|
#include "tree_nodes/i2c.hpp"
|
||||||
#include "tree_nodes/move_point.hpp"
|
#include "tree_nodes/move_point.hpp"
|
||||||
#include "tree_nodes/rotate.hpp"
|
#include "tree_nodes/rotate.hpp"
|
||||||
#include "tree_nodes/zero.hpp"
|
#include "tree_nodes/zero.hpp"
|
||||||
@ -26,6 +27,7 @@ namespace mg {
|
|||||||
factory.registerNodeType<mg::MovePointNode>("MovePoint", node());
|
factory.registerNodeType<mg::MovePointNode>("MovePoint", node());
|
||||||
factory.registerNodeType<mg::RotateNode>("RotateNode", node());
|
factory.registerNodeType<mg::RotateNode>("RotateNode", node());
|
||||||
factory.registerNodeType<mg::ZeroNode>("ZeroNode", node());
|
factory.registerNodeType<mg::ZeroNode>("ZeroNode", node());
|
||||||
|
factory.registerNodeType<mg::I2cNode>("I2CSignal", node());
|
||||||
factory.registerNodeType<mg::CalibWidthNode>("CalibWidth", node(), [this]() { return this->position(); });
|
factory.registerNodeType<mg::CalibWidthNode>("CalibWidth", node(), [this]() { return this->position(); });
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
29
mg_bt/src/tree_nodes/i2c.hpp
Normal file
29
mg_bt/src/tree_nodes/i2c.hpp
Normal file
@ -0,0 +1,29 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "behaviortree_ros2/bt_service_node.hpp"
|
||||||
|
#include "mg_msgs/srv/i2c.hpp"
|
||||||
|
|
||||||
|
namespace mg {
|
||||||
|
class I2cNode : public BT::RosServiceNode<mg_msgs::srv::I2c> {
|
||||||
|
public:
|
||||||
|
I2cNode(const std::string& name, const BT::NodeConfig& conf, const BT::RosNodeParams& params) :
|
||||||
|
BT::RosServiceNode<mg_msgs::srv::I2c>(name, conf, params) { }
|
||||||
|
|
||||||
|
static BT::PortsList providedPorts() {
|
||||||
|
return providedBasicPorts({ BT::InputPort<int>("Address", 42, {}),
|
||||||
|
BT::InputPort<int>("Data", 0, {}),
|
||||||
|
BT::OutputPort<int>("Result") });
|
||||||
|
}
|
||||||
|
|
||||||
|
bool setRequest(typename Request::SharedPtr& req) override {
|
||||||
|
req->addr = getInput<int>("Address").value_or(42);
|
||||||
|
req->data = getInput<int>("Result").value_or(0);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
BT::NodeStatus onResponseReceived(const typename Response::SharedPtr& resp) override {
|
||||||
|
setOutput<int>("Result", resp->resp.front());
|
||||||
|
return BT::NodeStatus::SUCCESS;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
@ -19,6 +19,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
|
|||||||
"action/Rotate.action"
|
"action/Rotate.action"
|
||||||
"srv/CalcPath.srv"
|
"srv/CalcPath.srv"
|
||||||
"srv/SendDouble.srv"
|
"srv/SendDouble.srv"
|
||||||
|
"srv/I2c.srv"
|
||||||
)
|
)
|
||||||
|
|
||||||
ament_package()
|
ament_package()
|
||||||
4
mg_msgs/srv/I2c.srv
Normal file
4
mg_msgs/srv/I2c.srv
Normal file
@ -0,0 +1,4 @@
|
|||||||
|
uint8 addr
|
||||||
|
uint8 data
|
||||||
|
---
|
||||||
|
uint8[] resp
|
||||||
Reference in New Issue
Block a user