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

Feature/publish encoder data #334

Open
wants to merge 27 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
d834ba8
first version for encoder data
Aug 5, 2022
3247915
refactor in the encoder reading feature
Aug 11, 2022
71fb0aa
touch up some files
Aug 17, 2022
66fc87d
Initial version of tests made for the encoder development
Aug 25, 2022
5efbf6d
Update include/psen_scan_v2/encoder_state_ros_conversion.h
PilzES Nov 11, 2022
555ce76
Sure
PilzES Nov 11, 2022
e3b44b9
include header missed
PilzES Nov 11, 2022
160e44b
Update launch/psen_scan_v2.launch
PilzES Nov 11, 2022
c151387
Update include/psen_scan_v2/ros_scanner_node.h
PilzES Nov 11, 2022
7ec7090
Update msg/EncoderState.msg
PilzES Nov 11, 2022
30b1aca
Update src/psen_scan_driver.cpp
PilzES Nov 11, 2022
546c19d
Update standalone/CMakeLists.txt
PilzES Nov 11, 2022
d2b9620
Update standalone/include/psen_scan_v2_standalone/data_conversion_lay…
PilzES Nov 11, 2022
8b88538
Update standalone/include/psen_scan_v2_standalone/data_conversion_lay…
PilzES Nov 11, 2022
5a11f5c
Update standalone/include/psen_scan_v2_standalone/laserscan.h
PilzES Nov 11, 2022
629b26b
Update standalone/src/data_conversion_layer/start_request_serializati…
PilzES Nov 11, 2022
35dbfcb
Update standalone/include/psen_scan_v2_standalone/data_conversion_lay…
PilzES Nov 11, 2022
df73987
update integrationtest_ros_scanner_node.cpp
Nov 11, 2022
6c993ef
Solve minor things of feature encoder data
Nov 14, 2022
073181e
Add new unit tests for encoder state rosconversions.
Nov 14, 2022
55257b0
Add encoder states at ScanDataEqual.
Nov 15, 2022
fa4d3ef
Small format change
Nov 15, 2022
f64b77e
Solve invalid case style.
Nov 15, 2022
842f074
Byte order review, swap between Big-Indian and Little-Indian.
Nov 15, 2022
6f7cfba
Aling code and rename function for endianSwap
Nov 29, 2022
897db60
Fix error on standalone tests
Nov 29, 2022
a3f5e57
Modify the UDP dumps to fix serialize/deserialize tests
Dec 2, 2022
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
Prev Previous commit
Next Next commit
Solve invalid case style.
  • Loading branch information
m-sanchez-rico committed Nov 15, 2022
commit f64b77edb5d255a3c68854147834befdf71d8f99
4 changes: 2 additions & 2 deletions include/psen_scan_v2/encoder_state_ros_conversion.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ psen_scan_v2::EncoderState toEncoderStateMsg(const psen_scan_v2_standalone::Enco
ros_message.header.stamp = ros::Time{}.fromNSec(encoder_state.timestamp());
ros_message.header.frame_id = frame_id;

ros_message.encoder_1 = encoder_state.getEncoder_1();
ros_message.encoder_2 = encoder_state.getEncoder_2();
ros_message.encoder_1 = encoder_state.getEncoder1();
ros_message.encoder_2 = encoder_state.getEncoder2();

return ros_message;
}
Expand Down
4 changes: 2 additions & 2 deletions standalone/include/psen_scan_v2_standalone/encoder_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,9 @@ class EncoderState
EncoderState() = default;
EncoderState(data_conversion_layer::monitoring_frame::encoder::EncoderData encoder_data, const int64_t& timestamp);
//! @return double containing the reading of the encoder 1.
double getEncoder_1() const;
double getEncoder1() const;
//! @return double containing the reading of the encoder 2.
double getEncoder_2() const;
double getEncoder2() const;
//! @return time[ns] of the monitoring frame this state is linked to.
int64_t timestamp() const;

Expand Down
4 changes: 2 additions & 2 deletions standalone/src/encoder_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,12 @@ EncoderState::EncoderState(data_conversion_layer::monitoring_frame::encoder::Enc
{
}

double EncoderState::getEncoder_1() const
double EncoderState::getEncoder1() const
{
return encoder_data_.encoder_1;
}

double EncoderState::getEncoder_2() const
double EncoderState::getEncoder2() const
{
return encoder_data_.encoder_2;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,8 @@ MATCHER_P(IOStateEq, io_state, "")

MATCHER_P(EncoderStateEq, encoder_state, "")
{
return Matches(DoubleEq(encoder_state.getEncoder_1()))(arg.getEncoder_1()) &&
Matches(DoubleEq(encoder_state.getEncoder_2()))(arg.getEncoder_2());
return Matches(DoubleEq(encoder_state.getEncoder1()))(arg.getEncoder1()) &&
Matches(DoubleEq(encoder_state.getEncoder2()))(arg.getEncoder2());
}

MATCHER_P(PointwiseIOStateEq, vec, "")
Expand Down
4 changes: 2 additions & 2 deletions standalone/test/unit_tests/api/unittest_encoder_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,14 +32,14 @@ TEST(EncoderStateTests, shouldReturnCorrectTimestamp)
TEST(EncoderStateTests, shouldReturnCorrectValueForEncoder1)
{
const EncoderState encoder_state{ EncoderData{ 12.0005 /*encoder_1*/, 25.786 /*encoder_2*/ }, 42 /*timestamp*/ };
const auto encoder_1 = encoder_state.getEncoder_1();
const auto encoder_1 = encoder_state.getEncoder1();
EXPECT_DOUBLE_EQ(encoder_1, 12.0005);
}

TEST(EncoderStateTests, shouldReturnCorrectValueForEncoder2)
{
const EncoderState encoder_state{ EncoderData{ 12.0005 /*encoder_1*/, 25.786 /*encoder_2*/ }, 42 /*timestamp*/ };
const auto encoder_2 = encoder_state.getEncoder_2();
const auto encoder_2 = encoder_state.getEncoder2();
EXPECT_DOUBLE_EQ(encoder_2, 25.786);
}

Expand Down
4 changes: 2 additions & 2 deletions standalone/test/unit_tests/api/unittest_laserscan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,8 +187,8 @@ TEST(LaserScanTest, testSetAndGetEncoderStates)
laser_scan->encoderStates(encoder_states);

ASSERT_EQ(laser_scan->encoderStates().size(), 1u);
EXPECT_EQ(laser_scan->encoderStates()[0].getEncoder_1(), state.getEncoder_1());
EXPECT_EQ(laser_scan->encoderStates()[0].getEncoder_2(), state.getEncoder_2());
EXPECT_EQ(laser_scan->encoderStates()[0].getEncoder1(), state.getEncoder1());
EXPECT_EQ(laser_scan->encoderStates()[0].getEncoder2(), state.getEncoder2());
EXPECT_EQ(laser_scan->encoderStates()[0].timestamp(), 65);
}

Expand Down
4 changes: 2 additions & 2 deletions test/unit_tests/unittest_encoder_state_rosconversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ TEST(EncoderStateRosConversionsTest, shouldContainCorrectStates)
psen_scan_v2_standalone::EncoderState encoder_state{encoder_data, 56 /*timestamp*/ };
psen_scan_v2::EncoderState ros_message = toEncoderStateMsg(encoder_state, "some_frame");

EXPECT_EQ(ros_message.encoder_1, encoder_state.getEncoder_1());
EXPECT_EQ(ros_message.encoder_2, encoder_state.getEncoder_2());
EXPECT_EQ(ros_message.encoder_1, encoder_state.getEncoder1());
EXPECT_EQ(ros_message.encoder_2, encoder_state.getEncoder2());
}

TEST(EncoderStateRosConversionsTest, shouldThrowOnNegativeTime)
Expand Down