Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Hotfix] add config for grpc port #46

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions include/akushon/action/model/action_name.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,12 @@ class ActionName
static const char * RIGHT_SIDEKICK;
static const char * KEEPER_SIT;
static const char * KEEPER_UP;
static const char * MIDDOWN_KEEPER;
static const char * MIDUP_KEEPER;
static const char * KEEPER_LEFT;
static const char * KEEPER_RIGHT;
static const char * KEEPER_LEFT_UP;
static const char * KEEPER_RIGHT_UP;

static const std::map<std::string, int> map;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class CallDataPublishSetJoints
public:
CallDataPublishSetJoints(
akushon_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string& path, rclcpp::Node::SharedPtr& node);
const std::string& path, const rclcpp::Node::SharedPtr& node);

protected:
void AddNextToCompletionQueue() override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class CallDataPublishSetTorques
public:
CallDataPublishSetTorques(
akushon_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string& path, rclcpp::Node::SharedPtr& node);
const std::string& path, const rclcpp::Node::SharedPtr& node);

protected:
virtual void AddNextToCompletionQueue() override;
Expand Down
2 changes: 1 addition & 1 deletion include/akushon/config/grpc/call_data_run_action.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class CallDataRunAction
public:
CallDataRunAction(
akushon_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string& path, rclcpp::Node::SharedPtr& node);
const std::string& path, const rclcpp::Node::SharedPtr& node);

protected:
void AddNextToCompletionQueue() override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class CallDataSubscribeCurrentJoints
public:
CallDataSubscribeCurrentJoints(
akushon_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string& path, rclcpp::Node::SharedPtr& node);
const std::string& path, const rclcpp::Node::SharedPtr& node);

protected:
void AddNextToCompletionQueue() override;
Expand Down
3 changes: 2 additions & 1 deletion include/akushon/config/grpc/config.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@ class ConfigGrpc

~ConfigGrpc();

void Run(uint16_t port, const std::string & path, rclcpp::Node::SharedPtr & node,
void Run(
const std::string & path, const rclcpp::Node::SharedPtr & node,
const std::shared_ptr<akushon::ActionManager> & action_manager);

private:
Expand Down
3 changes: 3 additions & 0 deletions include/akushon/config/utils/config.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#define AKUSHON__CONFIG__UTILS__CONFIG_HPP_

#include <fstream>
#include <nlohmann/json.hpp>
#include <string>

namespace akushon
Expand All @@ -35,6 +36,8 @@ class Config
std::string get_config() const;
void save_config(const std::string & actions_data);

nlohmann::json get_grpc_config() const;

private:
std::string path;
};
Expand Down
18 changes: 12 additions & 6 deletions src/akushon/action/model/action_name.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,13 +45,19 @@ const char * ActionName::LEFTWARD_UP = "leftward_up";
const char * ActionName::RIGHTWARD_UP = "rightward_up";
const char * ActionName::RIGHT_KICK = "right_kick";
const char * ActionName::LEFT_KICK = "left_kick";
const char * ActionName::RIGHT_KICK_SHORT = "right_kick_short";
const char * ActionName::LEFT_KICK_SHORT = "left_kick_short";
const char * ActionName::RIGHT_KICK_WIDE = "right_kick_wide";
const char * ActionName::LEFT_KICK_WIDE = "left_kick_wide";
const char * ActionName::LEFT_SIDEKICK = "left_sidekick";
const char * ActionName::RIGHT_SIDEKICK = "right_sidekick";
const char * ActionName::RIGHT_KICK_SHORT = "right_kick";
const char * ActionName::LEFT_KICK_SHORT = "walk_ready";
const char * ActionName::RIGHT_KICK_WIDE = "right_kick";
const char * ActionName::LEFT_KICK_WIDE = "left_kick";
const char * ActionName::LEFT_SIDEKICK = "left_kick";
const char * ActionName::RIGHT_SIDEKICK = "right_kick";
const char * ActionName::KEEPER_SIT = "keeper_sit";
const char * ActionName::KEEPER_UP = "keeper_up";
const char * ActionName::MIDDOWN_KEEPER = "middown_keeper";
const char * ActionName::MIDUP_KEEPER = "midup_keeper";
const char * ActionName::KEEPER_LEFT = "left_keeper";
const char * ActionName::KEEPER_RIGHT = "right_keeper";
const char * ActionName::KEEPER_LEFT_UP = "leftup_keeper";
const char * ActionName::KEEPER_RIGHT_UP = "rightup_keeper";

} // namespace akushon
4 changes: 4 additions & 0 deletions src/akushon/action/node/action_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,10 @@ void ActionManager::load_config(const std::string & path)
}

try {
if (name == "grpc") {
std::cout << "skipping grpc.json" << std::endl;
continue;
}
std::ifstream file(file_name);
nlohmann::json action_data = nlohmann::json::parse(file);

Expand Down
2 changes: 1 addition & 1 deletion src/akushon/config/grpc/call_data_publish_set_joints.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ namespace akushon
{
CallDataPublishSetJoints::CallDataPublishSetJoints(
akushon_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string& path, rclcpp::Node::SharedPtr& node)
const std::string& path, const rclcpp::Node::SharedPtr& node)
: CallData(service, cq, path), node_(node)
{
set_joints_publisher_ =
Expand Down
2 changes: 1 addition & 1 deletion src/akushon/config/grpc/call_data_publish_set_torques.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace akushon
{
CallDataPublishSetTorques::CallDataPublishSetTorques(
akushon_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string& path, rclcpp::Node::SharedPtr& node)
const std::string& path, const rclcpp::Node::SharedPtr& node)
: CallData(service, cq, path), node_(node)
{
set_torque_publisher_ =
Expand Down
2 changes: 1 addition & 1 deletion src/akushon/config/grpc/call_data_run_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ namespace akushon
{
CallDataRunAction::CallDataRunAction(
akushon_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string& path, rclcpp::Node::SharedPtr& node)
const std::string& path, const rclcpp::Node::SharedPtr& node)
: CallData(service, cq, path), node_(node)
{
run_action_publisher_ =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace akushon
{
CallDataSubscribeCurrentJoints::CallDataSubscribeCurrentJoints(
akushon_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string& path, rclcpp::Node::SharedPtr& node)
const std::string& path, const rclcpp::Node::SharedPtr& node)
: CallData(service, cq, path), node_(node)
{
current_joint_subscription_ =
Expand Down
18 changes: 11 additions & 7 deletions src/akushon/config/grpc/config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,17 +23,17 @@
#include <chrono>
#include <csignal>
#include <future>
#include <rclcpp/rclcpp.hpp>
#include <string>

#include "akushon/config/utils/config.hpp"
#include "rclcpp/rclcpp.hpp"
#include "akushon/config/grpc/call_data_get_config.hpp"
#include "akushon/config/grpc/call_data_load_config.hpp"
#include "akushon/config/grpc/call_data_save_config.hpp"
#include "akushon/config/grpc/call_data_publish_set_joints.hpp"
#include "akushon/config/grpc/call_data_publish_set_torques.hpp"
#include "akushon/config/grpc/call_data_subscribe_current_joints.hpp"
#include "akushon/config/grpc/call_data_run_action.hpp"
#include "akushon/config/grpc/call_data_save_config.hpp"
#include "akushon/config/grpc/call_data_subscribe_current_joints.hpp"
#include "akushon/config/utils/config.hpp"

using grpc::ServerBuilder;
using namespace std::chrono_literals;
Expand All @@ -49,10 +49,13 @@ ConfigGrpc::~ConfigGrpc()
cq_->Shutdown();
}

void ConfigGrpc::Run(uint16_t port, const std::string& path, rclcpp::Node::SharedPtr& node,
const std::shared_ptr<ActionManager>& action_manager)
void ConfigGrpc::Run(
const std::string & path, const rclcpp::Node::SharedPtr & node,
const std::shared_ptr<ActionManager> & action_manager)
{
std::string server_address = absl::StrFormat("0.0.0.0:%d", port);
Config config(path);
std::string server_address =
absl::StrFormat("0.0.0.0:%d", config.get_grpc_config()["port"].get<uint16_t>());

ServerBuilder builder;
builder.AddListeningPort(server_address, grpc::InsecureServerCredentials());
Expand Down Expand Up @@ -85,6 +88,7 @@ void ConfigGrpc::Run(uint16_t port, const std::string& path, rclcpp::Node::Share
}
});
std::this_thread::sleep_for(200ms);
async_server.detach();
}

} // namespace akushon
2 changes: 1 addition & 1 deletion src/akushon/config/node/config_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ ConfigNode::ConfigNode(rclcpp::Node::SharedPtr node, const std::string & path,
response->status = "SAVED";
}
);
config_grpc.Run(5060, path, node, action_manager);
config_grpc.Run(path, node, action_manager);
RCLCPP_INFO(rclcpp::get_logger("GrpcServers"), "grpc running");
}

Expand Down
12 changes: 11 additions & 1 deletion src/akushon/config/utils/config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@

#include "akushon/action/model/action_name.hpp"
#include "akushon/config/utils/config.hpp"
#include "nlohmann/json.hpp"

namespace akushon
{
Expand All @@ -47,6 +46,9 @@ std::string Config::get_config() const
for (auto i = path.size(); i < file_name.size() - 5; i++) {
action_name += file_name[i];
}
if (action_name == "grpc") {
continue;
}
std::cout << action_name << " | ";

std::ifstream file(action_file.path());
Expand All @@ -61,6 +63,14 @@ std::string Config::get_config() const
return actions_list.dump();
}

nlohmann::json Config::get_grpc_config() const
{
std::ifstream grpc_file(this->path + "grpc.json");
nlohmann::json grpc_data = nlohmann::json::parse(grpc_file);
grpc_file.close();
return grpc_data;
}

void Config::save_config(const std::string & actions_data)
{
nlohmann::json actions_list = nlohmann::json::parse(actions_data);
Expand Down
Loading