Skip to content

Commit b52d6b9

Browse files
fmauchFelix Exner
authored andcommitted
Apply suggestions from code review
1 parent 0b28fb5 commit b52d6b9

File tree

4 files changed

+11
-16
lines changed

4 files changed

+11
-16
lines changed

examples/dashboard_example.cpp

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -29,14 +29,8 @@ using namespace urcl;
2929
// better configuration system such as Boost.Program_options
3030
const std::string DEFAULT_ROBOT_IP = "127.0.0.1";
3131

32-
std::unique_ptr<DashboardClient> my_dashboard;
3332

3433
// We need a callback function to register. See UrDriver's parameters for details.
35-
void handleRobotProgramState(bool program_running)
36-
{
37-
// Print the text in green so we see it better
38-
std::cout << "\033[1;32mProgram running: " << std::boolalpha << program_running << "\033[0m\n" << std::endl;
39-
}
4034

4135
int main(int argc, char* argv[])
4236
{
@@ -51,6 +45,7 @@ int main(int argc, char* argv[])
5145

5246
// Making the robot ready for the program by:
5347
// Connect the the robot Dashboard
48+
std::unique_ptr<DashboardClient> my_dashboard;
5449
my_dashboard.reset(new DashboardClient(robot_ip));
5550
if (!my_dashboard->connect())
5651
{

examples/full_driver.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ const std::string INPUT_RECIPE = "examples/resources/rtde_input_recipe.txt";
4646
const std::string CALIBRATION_CHECKSUM = "calib_12788084448423163542";
4747

4848
std::unique_ptr<UrDriver> g_my_driver;
49-
std::unique_ptr<DashboardClient> my_dashboard;
49+
std::unique_ptr<DashboardClient> g_my_dashboard;
5050
vector6d_t g_joint_positions;
5151

5252
// We need a callback function to register. See UrDriver's parameters for details.
@@ -69,36 +69,36 @@ int main(int argc, char* argv[])
6969

7070
// Making the robot ready for the program by:
7171
// Connect the the robot Dashboard
72-
my_dashboard.reset(new DashboardClient(robot_ip));
73-
if (!my_dashboard->connect())
72+
g_my_dashboard.reset(new DashboardClient(robot_ip));
73+
if (!g_my_dashboard->connect())
7474
{
7575
URCL_LOG_ERROR("Could not connect to dashboard");
7676
return 1;
7777
}
7878

7979
// Stop program, if there is one running
80-
if (!my_dashboard->commandStop())
80+
if (!g_my_dashboard->commandStop())
8181
{
8282
URCL_LOG_ERROR("Could not send stop program command");
8383
return 1;
8484
}
8585

86-
// Power it on
87-
if (!my_dashboard->commandPowerOff())
86+
// Power it off
87+
if (!g_my_dashboard->commandPowerOff())
8888
{
8989
URCL_LOG_ERROR("Could not send Power off command");
9090
return 1;
9191
}
9292

9393
// Power it on
94-
if (!my_dashboard->commandPowerOn())
94+
if (!g_my_dashboard->commandPowerOn())
9595
{
9696
URCL_LOG_ERROR("Could not send Power on command");
9797
return 1;
9898
}
9999

100100
// Release the brakes
101-
if (!my_dashboard->commandBrakeRelease())
101+
if (!g_my_dashboard->commandBrakeRelease())
102102
{
103103
URCL_LOG_ERROR("Could not send BrakeRelease command");
104104
return 1;

examples/primary_pipeline.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ int main(int argc, char* argv[])
4848
robot_ip = std::string(argv[1]);
4949
}
5050

51-
// Parse how may seconds to run
51+
// Parse how many seconds to run
5252
int second_to_run = -1;
5353
if (argc > 2)
5454
{

src/ur/dashboard_client.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -143,7 +143,7 @@ bool DashboardClient::waitForReply(const std::string& command, const std::string
143143
// Send the request
144144
response = sendAndReceive(command + "\n");
145145

146-
// Check it the response was as expected
146+
// Check if the response was as expected
147147
if (std::regex_match(response, std::regex(expected)))
148148
{
149149
return true;

0 commit comments

Comments
 (0)