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

Added ability to use ROS params to static_transform_publisher #242

Open
wants to merge 2 commits into
base: noetic-devel
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
134 changes: 90 additions & 44 deletions tf/src/static_transform_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,10 @@ class TransformSender
{
public:
ros::NodeHandle node_;
//constructor
TransformSender(double x, double y, double z, double yaw, double pitch, double roll, ros::Time time, const std::string& frame_id, const std::string& child_frame_id)
{
tf::Quaternion q;
q.setRPY(roll, pitch,yaw);
q.setRPY(roll, pitch, yaw);
transform_ = tf::StampedTransform(tf::Transform(q, tf::Vector3(x,y,z)), time, frame_id, child_frame_id );
};
TransformSender(double x, double y, double z, double qx, double qy, double qz, double qw, ros::Time time, const std::string& frame_id, const std::string& child_frame_id) :
Expand All @@ -49,8 +48,6 @@ class TransformSender
//A pointer to the rosTFServer class
tf::TransformBroadcaster broadcaster;



// A function to call to send data periodically
void send (ros::Time time) {
transform_.stamp_ = time;
Expand All @@ -62,71 +59,120 @@ class TransformSender

};

void help()
{
printf("A command line utility for manually sending a transform.\n");
printf("It will periodicaly republish the given transform. \n");
printf("Usage: static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period(milliseconds) \n");
printf("OR \n");
printf("Usage: static_transform_publisher x y z qx qy qz qw frame_id child_frame_id period(milliseconds) \n");
printf("As an alternative, you may supply these arguments as ROS parameters (names as above). \n");
printf("\nThis transform is the transform of the coordinate frame from frame_id into the coordinate frame \n");
printf("of the child_frame_id. \n");
ROS_ERROR("static_transform_publisher exited due to not having the right number of arguments (9, 10 or 0)");
}

int main(int argc, char ** argv)
{
//Initialize ROS
ros::init(argc, argv,"static_transform_publisher", ros::init_options::AnonymousName);

if(argc == 11)
{
ros::Duration sleeper(atof(argv[10])/1000.0);

if (strcmp(argv[8], argv[9]) == 0)
ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", argv[8], argv[9]);
double period, x, y, z, rx, ry, rz, w;
std::string frame_id, child_frame_id;
bool is_quat;

if (argc == 11) {
x = atof(argv[1]);
y = atof(argv[2]);
z = atof(argv[3]);
rx = atof(argv[4]);
ry = atof(argv[5]);
rz = atof(argv[6]);
w = atof(argv[7]);
frame_id = argv[8];
child_frame_id = argv[9];
period = atof(argv[10]);
is_quat = true;
}
else if (argc == 10) {
x = atof(argv[1]);
y = atof(argv[2]);
z = atof(argv[3]);
rx = atof(argv[4]);
ry = atof(argv[5]);
rz = atof(argv[6]);
frame_id = argv[7];
child_frame_id = argv[8];
period = atof(argv[9]);
is_quat = false;
}
else if (argc == 1) {
try {
ros::param::get("~period", period);
ros::param::get("~x", x);
ros::param::get("~y", y);
ros::param::get("~z", z);

if (ros::param::has("~yaw")) {
ros::param::get("~yaw", rz);
ros::param::get("~pitch", ry);
ros::param::get("~roll", rx);
is_quat = false;
}
else {
ros::param::get("~qx", rz);
ros::param::get("~qy", ry);
ros::param::get("~qz", rx);
ros::param::get("~qw", w);
is_quat = true;
}

ros::param::get("~frame_id", frame_id);
ros::param::get("~child_frame_id", child_frame_id);
}
catch (ros::InvalidNameException& e) {
help();
return -1;
}
}
else {
help();
return -1;
}

TransformSender tf_sender(atof(argv[1]), atof(argv[2]), atof(argv[3]),
atof(argv[4]), atof(argv[5]), atof(argv[6]), atof(argv[7]),
ros::Time() + sleeper, //Future dating to allow slower sending w/o timeout
argv[8], argv[9]);
if (frame_id == child_frame_id) {
ROS_FATAL("target_frame and source frame are the same (%s, %s), this cannot work", child_frame_id.c_str(), frame_id.c_str());
}

ros::Duration sleeper(period/1000.0);

if (is_quat) {
TransformSender tf_sender(x, y, z, rx, ry, rz, w,
ros::Time() + sleeper, //Future dating to allow slower sending w/o timeout
frame_id, child_frame_id);

while(tf_sender.node_.ok())
{
tf_sender.send(ros::Time::now() + sleeper);
ROS_DEBUG("Sending transform from %s with parent %s\n", argv[8], argv[9]);
ROS_DEBUG("Sending transform from %s with parent %s\n", child_frame_id.c_str(), frame_id.c_str());
sleeper.sleep();
}

return 0;
}
else if (argc == 10)
{
ros::Duration sleeper(atof(argv[9])/1000.0);

if (strcmp(argv[7], argv[8]) == 0)
ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", argv[7], argv[8]);

TransformSender tf_sender(atof(argv[1]), atof(argv[2]), atof(argv[3]),
atof(argv[4]), atof(argv[5]), atof(argv[6]),
}
else {
TransformSender tf_sender(x, y, z, rz, ry, rx, // Note that yaw comes first here
ros::Time() + sleeper, //Future dating to allow slower sending w/o timeout
argv[7], argv[8]);


frame_id, child_frame_id);

while(tf_sender.node_.ok())
{
tf_sender.send(ros::Time::now() + sleeper);
ROS_DEBUG("Sending transform from %s with parent %s\n", argv[7], argv[8]);
ROS_DEBUG("Sending transform from %s with parent %s\n", child_frame_id.c_str(), frame_id.c_str());
sleeper.sleep();
}

return 0;

}
else
{
printf("A command line utility for manually sending a transform.\n");
printf("It will periodicaly republish the given transform. \n");
printf("Usage: static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period(milliseconds) \n");
printf("OR \n");
printf("Usage: static_transform_publisher x y z qx qy qz qw frame_id child_frame_id period(milliseconds) \n");
printf("\nThis transform is the transform of the coordinate frame from frame_id into the coordinate frame \n");
printf("of the child_frame_id. \n");
ROS_ERROR("static_transform_publisher exited due to not having the right number of arguments");
return -1;
}


}

14 changes: 14 additions & 0 deletions tf/static_transform_publisher_params_test.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<launch>

<node pkg="tf" type="static_transform_publisher" name="static_transform_publisher_params_test"
args="0 1 2 0.653 0.270 0.653 0.270 map test 10"/>

<node pkg="tf" type="static_transform_publisher" name="static_transform_publisher_params_test2">

<rosparam command="load" file="$(find tf)/static_transform_publisher_params_test.yaml"/>
<param name="frame_id" value="test"/>
<param name="child_frame_id" value="map_identity"/>
<param name="period" value="10"/>
</node>

</launch>
6 changes: 6 additions & 0 deletions tf/static_transform_publisher_params_test.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
x: -2.122209
y: -0.704436
z: 0
roll: -2.357453
pitch: -1.570796
yaw: 0.00000