38 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)
44 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) :
65 int main(
int argc,
char ** argv)
74 if (strcmp(argv[8], argv[9]) == 0)
75 ROS_FATAL(
"target_frame and source frame are the same (%s, %s) this cannot work", argv[8], argv[9]);
78 atof(argv[4]), atof(argv[5]), atof(argv[6]), atof(argv[7]),
87 ROS_DEBUG(
"Sending transform from %s with parent %s\n", argv[8], argv[9]);
97 if (strcmp(argv[7], argv[8]) == 0)
98 ROS_FATAL(
"target_frame and source frame are the same (%s, %s) this cannot work", argv[7], argv[8]);
101 atof(argv[4]), atof(argv[5]), atof(argv[6]),
110 ROS_DEBUG(
"Sending transform from %s with parent %s\n", argv[7], argv[8]);
119 printf(
"A command line utility for manually sending a transform.\n");
120 printf(
"It will periodicaly republish the given transform. \n");
121 printf(
"Usage: static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period(milliseconds) \n");
123 printf(
"Usage: static_transform_publisher x y z qx qy qz qw frame_id child_frame_id period(milliseconds) \n");
124 printf(
"\nThis transform is the transform of the coordinate frame from frame_id into the coordinate frame \n");
125 printf(
"of the child_frame_id. \n");
126 ROS_ERROR(
"static_transform_publisher exited due to not having the right number of arguments");
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
Set the quaternion using fixed axis RPY.
Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte...