Skip to content

Commit

Permalink
Apply clang-format
Browse files Browse the repository at this point in the history
  • Loading branch information
Tiryoh committed Jun 3, 2022
1 parent e7dc840 commit b9ab53f
Show file tree
Hide file tree
Showing 3 changed files with 160 additions and 78 deletions.
63 changes: 63 additions & 0 deletions .clang-format
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
BasedOnStyle: Google
AccessModifierOffset: -2
ConstructorInitializerIndentWidth: 2
AlignEscapedNewlinesLeft: false
AlignTrailingComments: true
AllowAllParametersOfDeclarationOnNextLine: false
AllowShortIfStatementsOnASingleLine: false
AllowShortLoopsOnASingleLine: false
AllowShortFunctionsOnASingleLine: None
AlwaysBreakTemplateDeclarations: true
AlwaysBreakBeforeMultilineStrings: false
BreakBeforeBinaryOperators: false
BreakBeforeTernaryOperators: false
BreakConstructorInitializersBeforeComma: true
BinPackParameters: true
ColumnLimit: 120
ConstructorInitializerAllOnOneLineOrOnePerLine: true
DerivePointerBinding: false
PointerBindsToType: true
ExperimentalAutoDetectBinPacking: false
IndentCaseLabels: true
MaxEmptyLinesToKeep: 1
NamespaceIndentation: None
ObjCSpaceBeforeProtocolList: true
PenaltyBreakBeforeFirstCallParameter: 19
PenaltyBreakComment: 60
PenaltyBreakString: 1
PenaltyBreakFirstLessLess: 1000
PenaltyExcessCharacter: 1000
PenaltyReturnTypeOnItsOwnLine: 90
SpacesBeforeTrailingComments: 2
Cpp11BracedListStyle: false
Standard: Auto
IndentWidth: 2
TabWidth: 2
UseTab: Never
IndentFunctionDeclarationAfterType: false
SpacesInParentheses: false
SpacesInAngles: false
SpaceInEmptyParentheses: false
SpacesInCStyleCastParentheses: false
SpaceAfterControlStatementKeyword: true
SpaceBeforeAssignmentOperators: true
ContinuationIndentWidth: 4
SortIncludes: false
SpaceAfterCStyleCast: false

# Configure each individual brace in BraceWrapping
BreakBeforeBraces: Custom

# Control of individual brace wrapping cases
BraceWrapping: {
AfterClass: 'true'
AfterControlStatement: 'true'
AfterEnum : 'true'
AfterFunction : 'true'
AfterNamespace : 'true'
AfterStruct : 'true'
AfterUnion : 'true'
BeforeCatch : 'true'
BeforeElse : 'true'
IndentBraces : 'false'
}
93 changes: 53 additions & 40 deletions raspicat_gazebo/src/motors_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,21 +19,25 @@
#include <ros/ros.h>
#include <std_srvs/Trigger.h>

namespace motors_sim {
class motors_sim final {
namespace motors_sim
{
class motors_sim final
{
public:
motors_sim(ros::NodeHandle &nodeHandle, ros::NodeHandle &private_nodeHandle,
std::string &initial_motor_power)
: nh_(nodeHandle), pnh_(private_nodeHandle),
init_mt_pw_(initial_motor_power) {
motors_sim(ros::NodeHandle& nodeHandle, ros::NodeHandle& private_nodeHandle, std::string& initial_motor_power)
: nh_(nodeHandle), pnh_(private_nodeHandle), init_mt_pw_(initial_motor_power)
{
readParameters();
initServiceServer();
initPubSub();
initTimerCb();
initialMotorPower();
};

~motors_sim() { checkCmdVelTimer_.stop(); };
~motors_sim()
{
checkCmdVelTimer_.stop();
};

private:
ros::NodeHandle nh_;
Expand All @@ -51,32 +55,35 @@ class motors_sim final {
bool in_cmdvel_ = false;
std::string init_mt_pw_;

void readParameters() {
void readParameters()
{
double publishRate;
pnh_.param("check_cmdvel_rate", publishRate, 10.0);
if (publishRate == 0.0) {
if (publishRate == 0.0)
{
checkCmdVelDuration_.fromSec(0.0);
ROS_WARN("The rate for checking the value of cmd_vel is 0.");
} else {
}
else
{
checkCmdVelDuration_.fromSec(1.0 / publishRate);
}
ROS_ASSERT(!checkCmdVelDuration_.isZero());
}

void initServiceServer() {
srv_motor_on_ = nh_.advertiseService<std_srvs::TriggerRequest,
std_srvs::TriggerResponse>(
"motor_on", [&](auto &req, auto &res) {
void initServiceServer()
{
srv_motor_on_ = nh_.advertiseService<std_srvs::TriggerRequest, std_srvs::TriggerResponse>(
"motor_on", [&](auto& req, auto& res) {
ROS_INFO("Called service motor_on.");
setPower(true);
res.message = "Motor On";
res.success = true;
return true;
});

srv_motor_off_ = nh_.advertiseService<std_srvs::TriggerRequest,
std_srvs::TriggerResponse>(
"motor_off", [&](auto &req, auto &res) {
srv_motor_off_ = nh_.advertiseService<std_srvs::TriggerRequest, std_srvs::TriggerResponse>(
"motor_off", [&](auto& req, auto& res) {
ROS_INFO("Called service motor_off.");
setPower(false);
pubZeroSimCmdVel();
Expand All @@ -86,50 +93,56 @@ class motors_sim final {
});
}

void initPubSub() {
sim_cmd_vel_publisher_ =
pnh_.advertise<geometry_msgs::Twist>("/sim_cmd_vel", 1);
void initPubSub()
{
sim_cmd_vel_publisher_ = pnh_.advertise<geometry_msgs::Twist>("/sim_cmd_vel", 1);

cmd_vel_subscriber_ = pnh_.subscribe<geometry_msgs::Twist>(
"/cmd_vel", 1, [&](const auto &msg) {
vel_ = *msg;
pubSimCmdVel(*msg);
last_cmdvel_ = ros::Time::now();
in_cmdvel_ = true;
});
cmd_vel_subscriber_ = pnh_.subscribe<geometry_msgs::Twist>("/cmd_vel", 1, [&](const auto& msg) {
vel_ = *msg;
pubSimCmdVel(*msg);
last_cmdvel_ = ros::Time::now();
in_cmdvel_ = true;
});
}

void initTimerCb() {
checkCmdVelTimer_ = pnh_.createTimer(checkCmdVelDuration_, [&](auto &) {
if (in_cmdvel_ and
ros::Time::now().toSec() - last_cmdvel_.toSec() >= 1.0) {
pubZeroSimCmdVel();
void initTimerCb()
{
checkCmdVelTimer_ = pnh_.createTimer(checkCmdVelDuration_, [&](auto&) {
if (in_cmdvel_ and ros::Time::now().toSec() - last_cmdvel_.toSec() >= 1.0)
{
pubZeroSimCmdVel();
}
});
}

void initialMotorPower() {
void initialMotorPower()
{
ROS_INFO("Initial motor_on.");
setPower(init_mt_pw_ == "on");
}

void setPower(bool is_on) { is_on_ = is_on; }
void setPower(bool is_on)
{
is_on_ = is_on;
}

void pubSimCmdVel(const geometry_msgs::Twist &sim_cmd_vel) {
void pubSimCmdVel(const geometry_msgs::Twist& sim_cmd_vel)
{
geometry_msgs::Twist zero_vel;
is_on_ ? sim_cmd_vel_publisher_.publish(sim_cmd_vel)
: sim_cmd_vel_publisher_.publish(zero_vel);
is_on_ ? sim_cmd_vel_publisher_.publish(sim_cmd_vel) : sim_cmd_vel_publisher_.publish(zero_vel);
}

void pubZeroSimCmdVel() {
void pubZeroSimCmdVel()
{
geometry_msgs::Twist zero_vel;
sim_cmd_vel_publisher_.publish(zero_vel);
}
};

} // namespace motors_sim
} // namespace motors_sim

int main(int argc, char **argv) {
int main(int argc, char** argv)
{
ros::init(argc, argv, "motors_sim");
ros::NodeHandle nh;
ros::NodeHandle pnh("~");
Expand Down
82 changes: 44 additions & 38 deletions raspicat_gazebo/src/ultrasonic_sensor_real_data_convert.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,22 +19,27 @@

#include "raspimouse_msgs/LightSensorValues.h"

namespace ultrasonic_sensor_real_data_convert {
class usensor_convert final{
namespace ultrasonic_sensor_real_data_convert
{
class usensor_convert final
{
public:
usensor_convert(ros::NodeHandle &nodeHandle) : pnh_(nodeHandle) {
usensor_convert(ros::NodeHandle& nodeHandle) : pnh_(nodeHandle)
{
readParameters();
initPubSub();
initTimerCb();
};

~usensor_convert() { usensorValuePublishTimer_.stop(); };
~usensor_convert()
{
usensorValuePublishTimer_.stop();
};

private:
ros::NodeHandle pnh_;
ros::Publisher usensor_pub_;
ros::Subscriber usensor_left_front_subscriber_,
usensor_left_left_side_subscriber_, usensor_right_front_subscriber_,
ros::Subscriber usensor_left_front_subscriber_, usensor_left_left_side_subscriber_, usensor_right_front_subscriber_,
usensor_right_side_subscriber_;
ros::Timer usensorValuePublishTimer_;
ros::Duration usensorPublishDuration_;
Expand All @@ -44,82 +49,83 @@ class usensor_convert final{
sensor_msgs::Range right_front_msg_;
sensor_msgs::Range right_side_msg_;

void readParameters() {
void readParameters()
{
double publishRate;
pnh_.param("publish_rate", publishRate, 10.0);
if (publishRate == 0.0) {
if (publishRate == 0.0)
{
usensorPublishDuration_.fromSec(0.0);
ROS_WARN("The rate for publishing the value of cmd_vel is 0.");
} else {
}
else
{
usensorPublishDuration_.fromSec(1.0 / publishRate);
}
ROS_ASSERT(!usensorPublishDuration_.isZero());
}

void initPubSub() {
usensor_pub_ =
pnh_.advertise<raspimouse_msgs::LightSensorValues>("/lightsensors", 1);
void initPubSub()
{
usensor_pub_ = pnh_.advertise<raspimouse_msgs::LightSensorValues>("/lightsensors", 1);

usensor_left_front_subscriber_ = pnh_.subscribe<sensor_msgs::Range>(
"/left_front_ultrasonic_sensor", 1,
[&](const auto &msg) { left_front_msg_ = *msg; });
"/left_front_ultrasonic_sensor", 1, [&](const auto& msg) { left_front_msg_ = *msg; });

usensor_left_left_side_subscriber_ = pnh_.subscribe<sensor_msgs::Range>(
"/left_side_ultrasonic_sensor", 1,
[&](const auto &msg) { left_side_msg_ = *msg; });
"/left_side_ultrasonic_sensor", 1, [&](const auto& msg) { left_side_msg_ = *msg; });

usensor_right_front_subscriber_ = pnh_.subscribe<sensor_msgs::Range>(
"/right_front_ultrasonic_sensor", 1,
[&](const auto &msg) { right_front_msg_ = *msg; });
"/right_front_ultrasonic_sensor", 1, [&](const auto& msg) { right_front_msg_ = *msg; });

usensor_right_side_subscriber_ = pnh_.subscribe<sensor_msgs::Range>(
"/right_side_ultrasonic_sensor", 1,
[&](const auto &msg) { right_side_msg_ = *msg; });
"/right_side_ultrasonic_sensor", 1, [&](const auto& msg) { right_side_msg_ = *msg; });
}
void initTimerCb() {
usensorValuePublishTimer_ = pnh_.createTimer(
usensorPublishDuration_, &usensor_convert::publishUsensorValue, this);

void initTimerCb()
{
usensorValuePublishTimer_ = pnh_.createTimer(usensorPublishDuration_, &usensor_convert::publishUsensorValue, this);
}

void publishUsensorValue(const ros::TimerEvent &) {
void publishUsensorValue(const ros::TimerEvent&)
{
raspimouse_msgs::LightSensorValues msg;
msg.left_forward =
limitValue(convetMetetrToMillimeter(left_front_msg_.range));
msg.left_side =
limitValue(convetMetetrToMillimeter(left_side_msg_.range));
msg.right_forward =
limitValue(convetMetetrToMillimeter(right_front_msg_.range));
msg.right_side =
limitValue(convetMetetrToMillimeter(right_side_msg_.range));
msg.left_forward = limitValue(convetMetetrToMillimeter(left_front_msg_.range));
msg.left_side = limitValue(convetMetetrToMillimeter(left_side_msg_.range));
msg.right_forward = limitValue(convetMetetrToMillimeter(right_front_msg_.range));
msg.right_side = limitValue(convetMetetrToMillimeter(right_side_msg_.range));

msg.sum_forward = msg.left_forward + msg.right_forward;
msg.sum_all = msg.sum_forward + msg.left_side + msg.right_side;

usensor_pub_.publish(msg);
}

float limitValue(float range_value) {
float limitValue(float range_value)
{
if (range_value <= 10)
range_value = 4095;
else if (range_value > 10 && range_value <= 19)
range_value += +20;
else if (range_value > 20 && range_value <= 29)
range_value += 10;
else if (range_value >= 3800) {
else if (range_value >= 3800)
{
range_value = 4095;
}
return range_value;
}

float convetMetetrToMillimeter(float &range_value) {
float convetMetetrToMillimeter(float& range_value)
{
return range_value * 1000;
}
};

} // namespace ultrasonic_sensor_real_data_convert
} // namespace ultrasonic_sensor_real_data_convert

int main(int argc, char **argv) {
int main(int argc, char** argv)
{
ros::init(argc, argv, "usensor_convert");
ros::NodeHandle pnh("~");

Expand Down

0 comments on commit b9ab53f

Please sign in to comment.